commit 2c599aaa512f9e74a1ddd6a8ba3fc0c1d01ab146 Author: Miguel Angel de Heras Date: Wed Feb 26 10:33:31 2025 +0100 first commit diff --git a/CraterLab_base_giratoria/include/README b/CraterLab_base_giratoria/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/CraterLab_base_giratoria/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/CraterLab_base_giratoria/include/constants.h b/CraterLab_base_giratoria/include/constants.h new file mode 100644 index 0000000..25b0cf0 --- /dev/null +++ b/CraterLab_base_giratoria/include/constants.h @@ -0,0 +1,9 @@ +#define DEBUG_M4 false +#define DEBUG_M7 false +#define PULSE_REV 400 +#define REDUCTION_XY 5 +#define REDUCTION_A 60 +const int EN[3] = {10, 7, 4}; +const int DIRP[3] = {9, 6, 3}; +const int PUL[3] = {8, 5, 2}; +const int FC[3] = {51, 53, 49}; \ No newline at end of file diff --git a/CraterLab_base_giratoria/include/interface.html b/CraterLab_base_giratoria/include/interface.html new file mode 100644 index 0000000..c06fdd2 --- /dev/null +++ b/CraterLab_base_giratoria/include/interface.html @@ -0,0 +1,259 @@ +// Plantilla HTML +const char *htmlTemplate = R"rawliteral( + + + + + + + + + + +

X0:

+ + + + + +
+ + + +

+ + +

X1:

+ + + + + +
+ + + +

+ + +

Y0:

+ + + + + +
+ + + +

+ Sincronizar con Intervalómetro +

+ + + + + + +)rawliteral"; \ No newline at end of file diff --git a/CraterLab_base_giratoria/include/main_m4.cpp b/CraterLab_base_giratoria/include/main_m4.cpp new file mode 100644 index 0000000..242622d --- /dev/null +++ b/CraterLab_base_giratoria/include/main_m4.cpp @@ -0,0 +1,416 @@ +#include +#include +#include +#include + +using namespace rtos; + +Thread sensorThread; + +#define x1_axis 0 +#define y0_axis 1 +#define x0_axis 2 + +#define RIGHT false +#define LEFT true +#define STOP 0 +#define ZERO 1 +#define CONTINUOUS 2 +#define ANGLE_MODE 3 + + +// Dispositivo 360 +int x0Degrees = 0; +unsigned long x0Duration = 10000; +int x1Degrees = 0; +unsigned long x1Duration = 10000; +int y0Degrees = 0; +unsigned long y0Duration = 10000; +bool syncx0WithInterval360 = false; +bool syncx1WithInterval360 = false; +bool syncy0WithInterval360 = false; +bool isAction[3] = {false, false, false}; +int mode = STOP; + + +#if defined(ARDUINO_GIGA_M7) + #define debug Serial +#elif defined(ARDUINO_GIGA_M4) + #define debug RPC +#endif + +#define TIME_PULSE_XY 2500 +#define TIME_PULSE_A 500 + +bool direction[3] = {RIGHT, RIGHT, RIGHT}; + +unsigned long time_fc_zero[3] = {millis(), millis(), millis()}; +bool enable_zero[3] = {true, true, true}; + +void search_zero() + { + time_fc_zero[x1_axis] = millis(); + while(digitalRead(FC[x1_axis])||((millis()-time_fc_zero[x1_axis])<10)) + { + digitalWrite(PUL[x1_axis], HIGH); + delayMicroseconds(2000); + digitalWrite(PUL[x1_axis], LOW); + delayMicroseconds(2000); + if(digitalRead(FC[x1_axis])) time_fc_zero[x1_axis] = millis(); + } + time_fc_zero[y0_axis] = millis(); + while(digitalRead(FC[y0_axis])||((millis()-time_fc_zero[y0_axis])<10)) + { + digitalWrite(PUL[y0_axis], HIGH); + delayMicroseconds(2000); + digitalWrite(PUL[y0_axis], LOW); + delayMicroseconds(2000); + if(digitalRead(FC[y0_axis])) time_fc_zero[y0_axis] = millis(); + }; + time_fc_zero[x0_axis] = millis(); + while(digitalRead(FC[x0_axis])||((millis()-time_fc_zero[x0_axis])<10)) + { + digitalWrite(PUL[x0_axis], HIGH); + delayMicroseconds(250); + digitalWrite(PUL[x0_axis], LOW); + delayMicroseconds(250); + if(digitalRead(FC[x0_axis])) time_fc_zero[x0_axis] = millis(); + } + } + +int angle_pulses[3] = {0, 0, 0}; //Varaible temporal de pulsos +float axis_angle[3] = {0, 0, 0}; //Angulo actual + +float angleRead(int axis) + { + int sensorReading = angle_pulses[axis]; + float reduction = REDUCTION_XY; + if (axis==2) reduction = REDUCTION_A; + return (360*sensorReading/(reduction*PULSE_REV)); + } + +int axis_pulses[3] = {0, 0, 0}; //Pulsos necesarios para llegar al angulo indicado +int axis_direction[3] = {1, 1, 0}; //Direccion de giro +int angle_pulses_MAX[3] = {0, 0, 0}; //Pulsos necesarios para dar una vuelta completa +int angle_pulses_ant[3] = {0, 0, 0}; //Varaible temporal de pulsos +bool flag_search[3] = {false, false, false}; +bool flag_equal[3] = {true, true, true}; +bool flag_refresh[3] = {false, false, false}; + +unsigned long time_axis[3] = { millis(), millis(), millis()}; +unsigned long time_parts[3] = {10, 10, 10}; +unsigned long time_pulse[3] = {TIME_PULSE_XY, TIME_PULSE_XY, TIME_PULSE_A}; +int ant_angle[3] = {0, 0, 0}; + +void stop_all() + { + for(int i=0; i<3; i++) flag_refresh[i] = false; + } + +#define RESOLUTION_ANGLE 0.25 +float axis_angle_ant[3] = {0,0,0}; + +void search_angle(int axis, int angle, unsigned long time_initial, unsigned long time_final) + { + if(isAction[axis]) + { + axis_angle[axis] = angleRead(axis); + if((axis_angle[axis]>((float)angle+RESOLUTION_ANGLE))||(axis_angle[axis]<((float)angle-RESOLUTION_ANGLE))) + { + if (axis_angle_ant[axis]!=axis_angle[axis]) + { + #if DEBUG_M4 + RPC.print(axis_angle[axis]); + RPC.print(" "); + RPC.println(angle); + #endif + axis_angle_ant[axis] = axis_angle[axis]; + } + if (flag_search[axis]) + { + flag_search[axis] = false; + #if DEBUG_M4 + RPC.print(axis_angle[axis]); + RPC.print(" "); + RPC.print(angle); + #endif + if (axis_angle[axis]<(angle + RESOLUTION_ANGLE)) direction[axis] = RIGHT; + else direction[axis] = LEFT; + if ((abs(axis_angle[axis])>360)||(abs(angle)>360))enable_zero[axis] = false; + else enable_zero[axis] = true; + if((axis==y0_axis)||(axis==x0_axis)) direction[axis]=!direction[axis]; + digitalWrite(DIRP[axis], direction[axis]); + if (axis!=x0_axis) axis_pulses[axis] = map(abs(angle-axis_angle[axis]), 0, 359, 0, PULSE_REV*REDUCTION_XY); + else axis_pulses[axis] = map(abs(angle-axis_angle[axis]), 0, 359, 0, PULSE_REV*REDUCTION_A); + time_pulse[axis] = ((1000/2)*(time_final-time_initial)/axis_pulses[axis]); //1000 es conversion de milisegundos a microsegundos entre dos porque es tiempo de 0 a 1 + if((time_pulse[axis]=((float)angle-RESOLUTION_ANGLE))) flag_refresh[axis] = false; + } + } + +unsigned long time_refresh_x = micros(); +unsigned long time_refresh_y = micros(); +unsigned long time_refresh_a = micros(); +bool state_x = false; +bool state_y = false; +bool state_a = false; +void refresh_steppers() + { + if(((micros()-time_refresh_x)>=time_pulse[x1_axis])&&(flag_refresh[x1_axis])) + { + time_refresh_x = micros(); + digitalWrite(PUL[x1_axis], state_x); + if(state_x) + { + if (direction[x1_axis]==RIGHT) angle_pulses[x1_axis]++; + else angle_pulses[x1_axis]--; + } + state_x = !state_x; + } + if(((micros()-time_refresh_y)>=time_pulse[y0_axis])&&(flag_refresh[y0_axis])) + { + time_refresh_y = micros(); + digitalWrite(PUL[y0_axis], state_y); + if(state_y) + { + if (direction[y0_axis]==LEFT) angle_pulses[y0_axis]++; + else angle_pulses[y0_axis]--; + } + state_y = !state_y; + } + if(((micros()-time_refresh_a)>=time_pulse[x0_axis])&&(flag_refresh[x0_axis])) + { + time_refresh_a = micros(); + digitalWrite(PUL[x0_axis], state_a); + if(state_a) + { + if (direction[x0_axis]==LEFT) angle_pulses[x0_axis]++; + else angle_pulses[x0_axis]--; + } + state_a = !state_a; + } + } + + +long startTimex = 0; +long startTimey = 0; +long startTimea = 0; +const int timeThreshold = 500; + +void f_x1_axis(){ //Funcion de paso por cero de la interrupcion del eje x + if (((millis() - startTimex) > timeThreshold)&&(enable_zero[x1_axis])) + { + if(angle_pulses[x1_axis]>0) angle_pulses_MAX[x1_axis] = angle_pulses[x1_axis]; //Varaible de pulsos maximos por vuelta + angle_pulses[x1_axis] = 0; //Varaible temporal de pulsos + startTimex = millis(); + } + } + +void f_y0_axis(){ //Funcion de paso por cero de la interrupcion del eje y + if (((millis() - startTimey) > timeThreshold)&&(enable_zero[y0_axis])) + { + if(angle_pulses[y0_axis]>0) angle_pulses_MAX[y0_axis] = angle_pulses[y0_axis]; //Varaible de pulsos maximos por vuelta + angle_pulses[y0_axis] = 0; //Varaible temporal de pulsos + startTimey = millis(); + } + } + +void f_x0_axis(){ //Funcion de paso por cero de la interrupcion del eje a + if (((millis() - startTimea) > timeThreshold)&&(enable_zero[x0_axis])) + { + if(angle_pulses[x0_axis]>0) angle_pulses_MAX[x0_axis] = angle_pulses[x0_axis]; //Varaible de pulsos maximos por vuelta + angle_pulses[x0_axis] = 0; //Varaible temporal de pulsos + startTimea = millis(); + } + } + + +/* +Functions on the M4 that returns axis +*/ +int AxisA_Read() { + int result = angle_pulses[x0_axis]; + return result; +} + +int AxisX_Read() { + int result = angle_pulses[x1_axis]; + return result; +} + +int AxisY_Read() { + int result = angle_pulses[y0_axis]; + return result; +} + +int read_value[10]; +int* decode_values(String inputString_rpc, int num_dec) + { + String str = inputString_rpc.substring(inputString_rpc.lastIndexOf(":") + 1); + read_value[0] = str.substring(0, str.indexOf(',')).toInt(); + for(int i=1; i +#include +#include +#include "RPC.h" +#include +#include "interface.html" +#include + +#define AP_MODE false + +// Inicializando RTOS +using namespace rtos; +Thread sensorThread; + +#define WIFI true + +#if WIFI + #include + char ssid[] = "Analogue_Hyperlapse_Camera"; // your network SSID (name) + char password[] = "CraterLab"; // your network password (use for WPA, or use as key for WEP) + IPAddress ip(192, 168, 8, 3); + IPAddress remote_ip(192, 168, 8, 4); + IPAddress gateway(192, 168, 8, 1); + IPAddress subnet(255, 255, 255, 0); + IPAddress dns(8, 8, 8, 8); //primaryDNS + // Crear el servidor en el puerto 80 + WiFiServer server(80); + char packetBuffer[255]; //buffer to hold incoming packet + char ReplyBuffer[] = "acknowledged"; // a string to send back + WiFiUDP Udp; + unsigned int localPort = 2390; // local port to listen on + unsigned int remotePort = 2392; // local port to send +#endif + +#define x1_axis 0 +#define y0_axis 1 +#define x0_axis 2 + +#define STOP 0 +#define ZERO 1 +#define CONTINUOUS 2 +#define ANGLE_MODE 3 + +// Motor +int motorSpeedValue = 25; +bool motorIsSpeedActive = false; +int motorIntervalFrames = 1; +int motorIntervalSeconds = 1; +bool motorIsIntervalActive = false; +int motorDirection = 1; + +// Shutter +int shutterFadePercent = 0; +int shutterFadeFrames = 50; +bool shutterSyncWithInterval = false; +bool shutterFadeInActive = false; +bool shutterFadeOutActive = false; + +// Óptica +int zoomValue = 50; +int focusValue = 50; +float diaphragmValue = 1.8; +bool syncWithIntervalOptics = false; + +// Dispositivo 360 +int x0Degrees = 0; +int x0Duration = 0; +int x1Degrees = 0; +int x1Duration = 0; +int y0Degrees = 0; +int y0Duration = 0; +bool syncWithInterval360 = false; + +//Sensores +float motorSpeedRead = 0; +float FadePercentRead = 0; +int zoomValueRead = 0; +int focusValueRead = 0; +float diaphragmValueRead = 0; +int x0DegreesRead = 0; +int x1DegreesRead = 0; +int y0DegreesRead = 0; + +int mode = CONTINUOUS; + +const char axis_c[] = {'x','y','a'}; + +float Motor_axis[3] = {0,0,0}; + +int read_value[10]; +int* decode_values(String inputString, int num_dec) + { + String str = inputString.substring(inputString.lastIndexOf(":") + 1); + read_value[0] = str.substring(0, str.indexOf(',')).toInt(); + for(int i=1; i doc; + deserializeJson(doc, body); + int save = true; + //DeserializationError error = deserializeJson(doc, body); + /*if (error) { + Serial.println("Error al parsear el JSON"); + return; + }*/ + + Serial.println("Procesando JSON..."); + String type = doc["type"]; + if((type=="test_360")||(type=="save_360")) + { + Serial.println(type); + if (type=="save_360") save = true; + else save = false; + String axis = doc["motor"]; + if (axis=="x0") + { + x0Degrees = doc["degrees"]; + x0Duration = doc["duration"]; + syncWithInterval360 = doc["syncWithInterval"]; + RPC.println("/axisA:" + String(x0Degrees) + "," + String(x0Duration) + "," + String(syncWithInterval360) + "," + String(save)); + } + else if (axis=="x1") + { + x1Degrees = doc["degrees"]; + x1Duration = doc["duration"]; + syncWithInterval360 = doc["syncWithInterval"]; + RPC.println("/axisX:" + String(x1Degrees) + "," + String(x1Duration) + "," + String(syncWithInterval360) + "," + String(save)); + } + else if (axis=="y0") + { + y0Degrees = doc["degrees"]; + y0Duration = doc["duration"]; + syncWithInterval360 = doc["syncWithInterval"]; + RPC.println("/axisY:" + String(y0Degrees) + "," + String(y0Duration) + "," + String(syncWithInterval360) + "," + String(save)); + } + } + else Serial.println("No reconocido"); +} + +/* +This thread calls the sensorThread() function remotely +every second. Result is printed to the RPC1 stream. +*/ + +void requestReading() { + while (true) { + delay(25); + Motor_axis[x1_axis] = RPC.call("AxisX").as(); + Motor_axis[y0_axis] = RPC.call("AxisY").as(); + Motor_axis[x0_axis] = RPC.call("AxisA").as(); + x0DegreesRead = 360*Motor_axis[x0_axis]/(REDUCTION_A*PULSE_REV); + y0DegreesRead = 360*Motor_axis[y0_axis]/(REDUCTION_XY*PULSE_REV); + x1DegreesRead = 360*Motor_axis[x1_axis]/(REDUCTION_XY*PULSE_REV); + + } +} + +int mode_Read() { + int result = mode; + return result; +} + +void setup() { + Serial.begin(1000000); + RPC.begin(); //boots M4 + #if WIFI + #if AP_MODE + int status = WL_IDLE_STATUS; + // Create open network. Change this line if you want to create an WEP network: + WiFi.config(ip, dns, gateway, subnet); + status = WiFi.beginAP(ssid, password); + if (status != WL_AP_LISTENING) { + Serial.println("Creating access point failed"); + // don't continue + while (true) + ; + } + #else + WiFi.config(ip, dns, gateway, subnet); + WiFi.begin(ssid, password); + while (WiFi.status() != WL_CONNECTED) + { + delay(1000); + Serial.print("."); + } + #endif + Serial.println(); + Serial.println("Conectado a WiFi!"); + Serial.print("Dirección IP: "); + Serial.println(WiFi.localIP()); + #endif + while (digitalRead(FC[x0_axis])||digitalRead(FC[x1_axis])||digitalRead(FC[y0_axis])); + // Enable Server + server.begin(); + // Enable UDP + Udp.begin(localPort); + //Starts a new thread that loops the requestReading() function + sensorThread.start(requestReading); +} + +void readUDP() + { + int packetSize = Udp.parsePacket(); + if (packetSize) { + #if DEBUG_M7 + Serial.print("Received packet of size "); + Serial.println(packetSize); + Serial.print("From "); + IPAddress remoteIp = Udp.remoteIP(); + Serial.print(remoteIp); + Serial.print(", port "); + Serial.println(Udp.remotePort()); + #endif + // read the packet into packetBufffer + int len = Udp.read(packetBuffer, 255); + if (len > 0) { + packetBuffer[len] = 0; + } + RPC.println(packetBuffer); + #if DEBUG_M7 + Serial.println("Contents:"); + Serial.println(packetBuffer); + #endif + } + } + +void loop() { + WiFiClient client = server.available(); + if (client) { + #if DEBUG_M7 + Serial.println("Nuevo cliente conectado"); + #endif + String request = ""; + bool isPostRequest = false; + + while (client.connected()) { + if (client.available()) { + char c = client.read(); + request += c; + + // Identificar si es una solicitud POST + if (request.indexOf("POST") >= 0) { + isPostRequest = true; + } + + // Si se encuentra el final de la solicitud + if (c == '\n' && request.endsWith("\r\n\r\n")) { + #if DEBUG_M7 + Serial.println("Solicitud recibida:"); + Serial.println(request); + #endif + + if (isPostRequest) { + String body = ""; + while (client.available()) { + body += (char)client.read(); + } + #if DEBUG_M7 + Serial.println("Cuerpo del mensaje recibido:"); + Serial.println(body); + #endif + // Llamamos a la función para procesar la petición POST + handlePostRequest(body); + // Respuesta al cliente + client.println("HTTP/1.1 200 OK"); + client.println("Content-type:text/plain"); + client.println(); + client.println("Datos enviados correctamente"); + } else if (request.indexOf("GET /sensors") >= 0) { // actualiza fps en interface + // Respuesta para la ruta /motorSpeed + client.println("HTTP/1.1 200 OK"); + client.println("Content-Type: application/json"); + client.println(); + String response = "{\"sensors\":[" + String(x0DegreesRead) + "," + String(x1DegreesRead) + "," + String(y0DegreesRead) + "]}"; + client.print(response); + } else { + // Respuesta para servir la interfaz HTML + client.println("HTTP/1.1 200 OK"); + client.println("Content-type:text/html"); + client.println(); + client.print(htmlTemplate); + } + break; + } + } + } + client.stop(); + #if DEBUG_M7 + Serial.println("Cliente desconectado"); + #endif + } + readUDP(); + #if DEBUG_M7 + String buffer = ""; + + while (RPC.available()) { + + buffer += (char)RPC.read(); // Fill the buffer with characters + + } + + if (buffer.length() > 0) { + + Serial.print(buffer); + + } + #endif +} \ No newline at end of file diff --git a/CraterLab_base_giratoria/lib/README b/CraterLab_base_giratoria/lib/README new file mode 100644 index 0000000..6debab1 --- /dev/null +++ b/CraterLab_base_giratoria/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in a an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/CraterLab_base_giratoria/platformio.ini b/CraterLab_base_giratoria/platformio.ini new file mode 100644 index 0000000..48ffa7d --- /dev/null +++ b/CraterLab_base_giratoria/platformio.ini @@ -0,0 +1,30 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; https://docs.platformio.org/page/projectconf.html + +[env:ARDUINO_GIGA_M7] +;platform = https://github.com/dberlin/platform-ststm32.git#develop +;platform = https://github.com/dberlin/platform-ststm32 +platform = ststm32 +board = giga_r1_m7 +framework = arduino +monitor_speed = 1000000 +;upload_port = COM16 +board_build.arduino.flash_layout = 75_25 ;50_50, 75_25, 100_0 +lib_deps = bblanchon/ArduinoJson@^7.2.0 + +[env:ARDUINO_GIGA_M4] +;platform = https://github.com/dberlin/platform-ststm32.git#develop +platform = ststm32 +board = giga_r1_m4 +framework = arduino +monitor_speed = 1000000 +;upload_port = COM16 +board_build.arduino.flash_layout = 75_25 ;50_50, 75_25, 100_0 +;board_build.arduino.flash_layout = 100_0 ;50_50, 75_25, 100_0 \ No newline at end of file diff --git a/CraterLab_base_giratoria/src/main.cpp b/CraterLab_base_giratoria/src/main.cpp new file mode 100644 index 0000000..527a453 --- /dev/null +++ b/CraterLab_base_giratoria/src/main.cpp @@ -0,0 +1,5 @@ +#if defined(ARDUINO_GIGA_M7) + #include +#elif defined(ARDUINO_GIGA_M4) + #include +#endif \ No newline at end of file diff --git a/CraterLab_base_giratoria/test/README b/CraterLab_base_giratoria/test/README new file mode 100644 index 0000000..9b1e87b --- /dev/null +++ b/CraterLab_base_giratoria/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Test Runner and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html diff --git a/CraterLab_camera/include/README b/CraterLab_camera/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/CraterLab_camera/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/CraterLab_camera/include/constants.h b/CraterLab_camera/include/constants.h new file mode 100644 index 0000000..ccab64e --- /dev/null +++ b/CraterLab_camera/include/constants.h @@ -0,0 +1,42 @@ +#define FORWARD 0 +#define BACKWARD 1 +#define STOP 0 +#define IN 1 +#define OUT 2 +#define IN_OUT 3 +#define FPS_MOTOR 4 + +//Definicion de los pines del shift register +#define Data_pin 8 +#define Clock_pin 4 +#define Latch_pin 12 +#define Enable 7 + +//Definicion de los Motores 0,1,2,3 en el shift register +#define M2A 0 +#define M1A 1 +#define M0A 2 +#define M0B 3 +#define M1B 4 +#define M3A 5 +#define M2B 6 +#define M3B 7 + +//Definicion de los enable (PWM) de los Motores 0,1,2,3 en las gpio del Arduino +#define EN0 11 +#define EN1 3 +#define EN2 5 +#define EN3 6 + +//Definicion del Motor 4 +#define EN_M4 33 +#define R_M4 10 +#define L_M4 9 + +//Definicion de los pines de los sensores +#define sensor_fps 20 +#define sensor_lineal_motor A0 + +//Definicion de los limites del sensor lineal +#define LINEAL_MAX 478 +#define LINEAL_MIN 0 \ No newline at end of file diff --git a/CraterLab_camera/include/interface.html b/CraterLab_camera/include/interface.html new file mode 100644 index 0000000..ec74d9a --- /dev/null +++ b/CraterLab_camera/include/interface.html @@ -0,0 +1,452 @@ +// Plantilla HTML +const char *htmlTemplate = R"rawliteral( + + + + + + + + +
+

Control Bolex Paillard

+
+ +

Motor Cámara

+ +

Speed

+ + + 24 fps + + Activar Speed + +

Intervalómetro:

+ + + + + Activar Intervalómetro + +

Dirección:

+ Forward + Backward +

+ + + + +
+ +
+ +

Shutter

+

Fade In/Out Frames:

+

% apertura inicial: 50

+ + +

Número de frames: 50

+ + +

Fade Activación:

+ Activar Fade In + Activar Fade Out +

+ Sincronizar con Intervalómetro + +

+ + +
+ +
+ +

Monitor de Cámara

+ +
+ +
+ +

Óptica

+

Zoom:

+

Valor de zoom: 50

+ + +

Foco:

+

Valor de foco: 50

+ + +

Diafragma:

+ +

+ Sincronizar con Intervalómetro +

+ + + +
+ +
+ +

Dispositivo 360

+ + +
+ +
+ +

Rodaje

+ + + +

+
+
+ + + + + + +)rawliteral"; \ No newline at end of file diff --git a/CraterLab_camera/include/main_m4.cpp b/CraterLab_camera/include/main_m4.cpp new file mode 100644 index 0000000..a8861a3 --- /dev/null +++ b/CraterLab_camera/include/main_m4.cpp @@ -0,0 +1,539 @@ +#include +#include +//#include +//#include +#include +#include "constants.h" + +#define DEBUG_M4 false +#define MIN_SPEED 55 + +// Motor +int motorSpeedValue = 24; +bool motorIsSpeedActive = false; +int motorIntervalFrames = 1; +int motorIntervalSeconds = 1; +bool motorIsIntervalActive = false; +bool motorDirection = 1; + +// Shutter +int shutterFadePercent = 0; +int shutterFadeFrames = 50; +bool shutterSyncWithInterval = false; +bool shutterFadeInActive = false; +bool shutterFadeOutActive = false; + +// Óptica +int zoomValue = 50; +int focusValue = 50; +float diaphragmValue = 1.8; +bool syncWithIntervalOptics = false; + +bool closed=false; +bool isAction=false; + +#if PID_ENABLE + // ************************************************ Variables PID ***************************************************************** + double Setpoint = 0.0, Input = 0.0, Output = 0.0; // Setpoint=Posición designada; Input=Posición del motor; Output=Tensión de salida para el motor. + double kp = 0.0, ki = 0.0, kd = 0.0; // Constante proporcional, integral y derivativa. + double outMax = 0.0, outMin = 0.0; // Límites para no sobrepasar la resolución del PWM. + // **************************************************** Otras Variables *********************************************************** + volatile long contador = 0; // En esta variable se guardará los pulsos del encoder y que interpreremos como distancia (o ángulo si ese fuese el caso). + byte ant = 0, act = 0; // Sólo se utiliza los dos primeros bits de estas variables y servirán para decodificar el encoder. (ant=anterior, act=actual.) + byte cmd = 0; // Un byte que utilizamos para la comunicación serie. (cmd=comando.) + unsigned int tmp = 0; // Variable que utilizaremos para poner el tiempo de muestreo. + const byte ledok = 13; // El pin 13 de los Arduinos tienen un led que utilizo para mostrar que el motor ya ha llegado a la posición designada. + // ******************************************************************************************************************************** + + PID myPID(&Input, &Output, &Setpoint, 0.0, 0.0, 0.0, DIRECT); // Parámetros y configuración para invocar la librería. +#endif + +// parameters: (data pin, clock pin, latch pin) +ShiftRegister74HC595<1> sr(Data_pin, Clock_pin, Latch_pin); +const int EN_MOTOR[4] = {EN0, EN1, EN2, EN3}; +const int MA_MOTOR[4] = {M0A, M1A, M2A, M3A}; +const int MB_MOTOR[4] = {M0B, M1B, M2B, M3B}; +const long TIME_LINEAL_MAX[6] = {4150, 670, 4250, 6200, 4000, 4000 }; //ms + +void backward(int motor, int SPEED) + { + if(motor<4) + { + sr.set(MA_MOTOR[motor], HIGH); + sr.set(MB_MOTOR[motor], LOW); + analogWrite(EN_MOTOR[motor], SPEED); + } + else + { + analogWrite(L_M4, SPEED); + analogWrite(R_M4, 0); + } + + } + +void forward(int motor, int SPEED) + { + if(motor<4) + { + sr.set(MA_MOTOR[motor], LOW); + sr.set(MB_MOTOR[motor], HIGH); + analogWrite(EN_MOTOR[motor], SPEED); + } + else + { + analogWrite(L_M4, 0); + analogWrite(R_M4, SPEED); + } + + } + +void stop(int motor) + { + + if(motor<4) + { + analogWrite(EN_MOTOR[motor], 0); + sr.set(MA_MOTOR[motor], LOW); + sr.set(MB_MOTOR[motor], LOW); + } + else + { + analogWrite(L_M4, 0); + analogWrite(R_M4, 0); + } + } + +float time_move_for_move_position_motor[6] = {0, 0, 0, 0, 0, 0}; +unsigned long time_refresh_position_motor[6] = { millis(), millis(), millis(), millis(), millis(), millis()}; +float position_motor[6] = { 0, 0, 0, 0, 0, 0}; +float position_motor_objective[6] = { 0, 0, 0, 0, 0, 0}; +bool moving_position_motor[6] = { false, false, false, false, false, false}; + +void config_position_motor(int motor, float position) //Configuracion posicion en % motor + { + if((position!=position_motor[motor])&&(!moving_position_motor[motor])) + { + if(motor==0) + { + if(position>position_motor[motor]) forward(motor,255); + else backward(motor,255); + position_motor_objective[motor] = position; + moving_position_motor[motor] = true; + } + else + { + time_move_for_move_position_motor[motor] = (abs(position_motor[motor]-position)*TIME_LINEAL_MAX[motor])/100.; + if(position>position_motor[motor]) forward(motor,255); + else backward(motor,255); + time_refresh_position_motor[motor] = millis(); + position_motor_objective[motor] = position; + moving_position_motor[motor] = true; + //RPC.println("/debug:" + String(position_motor[motor]) + "," + String(position) + "," + String(millis()-time_refresh_position_motor[motor]) + "," + String(time_move_for_move_position_motor[motor]) + "," + "INI"); + //Serial.println(time_move_for_move_position_motor[motor]); + } + } + } + +bool state_smotor[6] = { false, false, false, false, false, false}; + +void config_speed_motor(int motor, int direction, int speed) //Configuracion velocidad motor + { + closed = false; + if(direction==FORWARD) forward(motor,speed); + else if(direction==BACKWARD) backward(motor,speed); + if(speed>0) state_smotor[motor] = true; + else state_smotor[motor] = false; + } + + +volatile float fps_read = 0; +volatile float fps_temp = 0; +unsigned long time_sec= millis(); +unsigned long time_fps = micros(); + +static volatile unsigned long lastTimeDebounce = 0; //Tiempo del rebote +static volatile bool force_stop = false; //Tiempo del rebote + +void fps_count_state() { + if((digitalRead(sensor_fps)&&(micros()-lastTimeDebounce>= 100))&&(!closed)) + { + lastTimeDebounce = micros(); + fps_temp = 1000000./(float)(micros()-time_fps); + if(fps_temp<70) fps_read = fps_temp; + time_fps = micros(); + if((millis()-time_sec)>=1000) + { + //RPC.println(fps_read); + time_sec = millis(); + } + } + else if((digitalRead(sensor_fps)&&(micros()-lastTimeDebounce >= 150))&&(closed)) + { + lastTimeDebounce = micros(); + closed = false; + force_stop = true; + } +} + +int interval_direction[6] = {0, 0, 0, 0, 0, 0}; +int interval_frames[6] = {0, 0, 0, 0, 0, 0}; +unsigned long interval_time[6] = {0, 0, 0, 0, 0, 0}; +int frames_count[6] = {0, 0, 0, 0, 0, 0}; +unsigned long time_interval_count[6] = {0, 0, 0, 0, 0, 0}; +void config_interval_motor(int direction, int Frames, int Seconds) //Configuracion velocidad motor + { + closed = false; + interval_direction[FPS_MOTOR] = direction; + interval_frames[FPS_MOTOR] = Frames; + interval_time[FPS_MOTOR] = Seconds*1000; + frames_count[FPS_MOTOR] = 0; + time_interval_count[FPS_MOTOR] = millis(); + } + +float inc_position_fade = 0; +int fade_direction = 0; +void config_automatic_fade(int shutterFadeFrames, int shutterSyncWithInterval, int shutterFadeInActive, int shutterFadeOutActive) //Configuracion fade + { + + if((shutterFadeInActive)&&(!shutterFadeOutActive)) + { + fade_direction=IN; + inc_position_fade = (100-position_motor[0])/(float)shutterFadeFrames; + } + else if((!shutterFadeInActive)&&(shutterFadeOutActive)) + { + fade_direction=OUT; + inc_position_fade = (position_motor[0])/(float)shutterFadeFrames; + } + else if((shutterFadeInActive)&&(shutterFadeOutActive)) + { + fade_direction=IN_OUT; + inc_position_fade = (100)/(float)shutterFadeFrames; + } + else fade_direction=STOP; + } + +void config_optics(int zoomValue, int focusValue, int diaphragmValue, int syncWithIntervalOptics) //Configuracion de las opticas + { + config_position_motor(1, zoomValue); + config_position_motor(2, focusValue); + config_position_motor(3, map(int(diaphragmValue*10), 19, 220, 0, 100)); + } + +void secure_stop(int direction) + { + config_speed_motor(FPS_MOTOR, direction, 0); + delay(150); + if (!digitalRead(sensor_fps)) + { + config_speed_motor(FPS_MOTOR, direction, MIN_SPEED); + closed = true; + } + } + +void next_frame(int direction) + { + config_speed_motor(FPS_MOTOR, motorDirection, MIN_SPEED); + closed = true; + } + +#define NUM 20. +int read_lineal_motor() + { + int value = 0; + for (int i=0; i<10; i++) value += analogRead(sensor_lineal_motor); + return value/10; + } + +void ini_motors() + { + //forward(0,255); + while (read_lineal_motor()>LINEAL_MAX) forward(0,255); + stop(0); + while (read_lineal_motor()(unsigned long)time_move_for_move_position_motor[i])&&(moving_position_motor[i])) + { + stop(i); + position_motor[i] = position_motor_objective[i]; + moving_position_motor[i] = false; + //RPC.println("/debug:" + String(position_motor[i]) + "," + String(position_motor_objective[i]) + "," + String(millis()-time_refresh_position_motor[i]) + "," + String(time_move_for_move_position_motor[i]) + "," + "END"); + } + } + } + +int change_direction_inout = 1; + +void refresh_interval_motors() + { + if((((millis()-time_interval_count[FPS_MOTOR])>=interval_time[FPS_MOTOR])&&(interval_frames[FPS_MOTOR]!=frames_count[FPS_MOTOR]))&&(isAction)) + { + frames_count[FPS_MOTOR]++; + time_interval_count[FPS_MOTOR] = millis(); + if(frames_count[FPS_MOTOR]>=interval_frames[FPS_MOTOR]) isAction=false; + if (shutterSyncWithInterval) + { + float value_position=0; + if(fade_direction==IN) + { + value_position = position_motor[0] + inc_position_fade; + if (value_position>100) value_position=100; + config_position_motor(0, value_position); + } + else if(fade_direction==OUT) + { + value_position = position_motor[0] - inc_position_fade; + if (value_position<0) value_position=0; + config_position_motor(0, value_position); + } + else if(fade_direction==IN_OUT) + { + if (((position_motor[0] + inc_position_fade)>100)&&(change_direction_inout==1)) change_direction_inout=-1; + else if (((position_motor[0] - inc_position_fade)<0)&&(change_direction_inout==-1)) change_direction_inout=1; + value_position = position_motor[0] + change_direction_inout*inc_position_fade; + RPC.println("/fade:" + String(position_motor[0]) + "," + String(change_direction_inout) + "," + String(inc_position_fade) + "," + String(0) + "," + String(shutterFadeOutActive)); + config_position_motor(0, value_position); + } + //else value_position = position_motor[0]; + + } + next_frame(interval_direction[FPS_MOTOR]); + } + } + +float fps_request = 24; +uint8_t speed_request = 0; +unsigned long time_adjust = millis(); + +/* +Functions on the M4 that returns FPS +*/ +int fpsRead() { + int result = fps_read; + return result; +} + +int read_value[10]; +int* decode_values(String inputString_rpc, int num_dec) + { + String str = inputString_rpc.substring(inputString_rpc.lastIndexOf(":") + 1); + read_value[0] = str.substring(0, str.indexOf(',')).toInt(); + for(int i=1; i0) motorSpeedValue = map(motorSpeedValue, 24, 48, 146, 192); //Fake fps + if (motorSpeedValue>0) motorSpeedValue = map(motorSpeedValue, 0, 48, 0, 255); //Fake fps + //if (motorSpeedValue>0) motorSpeedValue = 255; + if (value[3]==false) //Si es falso, se ejecuta, sino se guarda sin ejecutar + { + if (motorSpeedValue==0) + { + isAction = false; + secure_stop(motorDirection); + } + else config_speed_motor(value[0], motorDirection, motorSpeedValue); + } + } + else if (inputString_rpc.startsWith("/i_motor:")) //Interval Motor + { + int* value = decode_values(inputString_rpc, 5); + #if DEBUG_M4 + RPC.print("Recibido Interval M4: "); + RPC.println(inputString_rpc); + for(int i=0; i<5; i++) RPC.println(value[i]); + #endif + motorDirection = value[1]; + motorIntervalFrames = value[2]; + motorIntervalSeconds = value[3]; + motorIsIntervalActive = true; + motorIsSpeedActive = false; + if (value[4]==false) //Si es falso, se ejecuta, sino se guarda sin ejecutar + { + isAction = true; + config_interval_motor(motorDirection, motorIntervalFrames, motorIntervalSeconds); + } + + } + else if (inputString_rpc.startsWith("/fade:")) //Fade configuration + { + int* value = decode_values(inputString_rpc, 6); + #if DEBUG_M4 + RPC.print("Recibido fade M4: "); + RPC.println(inputString_rpc); + for(int i=0; i<6; i++) RPC.println(value[i]); + #endif + shutterFadePercent = value[0]; + shutterFadeFrames = value[1]; + shutterSyncWithInterval = value[2]; + shutterFadeInActive = value[3]; + shutterFadeOutActive = value[4]; + //RPC.println("/fade:" + String(shutterFadePercent) + "," + String(shutterFadeFrames) + "," + String(shutterSyncWithInterval) + "," + String(shutterFadeInActive) + "," + String(shutterFadeOutActive)); + config_position_motor(0, shutterFadePercent); + } + else if (inputString_rpc.startsWith("/optics:")) //Optics configuration + { + int* value = decode_values(inputString_rpc, 5); + #if DEBUG_M4 + RPC.print("Recibido optics M4: "); + RPC.println(inputString_rpc); + for(int i=0; i<5; i++) RPC.println(value[i]); + #endif + zoomValue = value[0]; + focusValue = value[1]; + diaphragmValue = value[2]; + syncWithIntervalOptics = value[3]; + if (value[4]==false) //Si es falso, se ejecuta, sino se guarda sin ejecutar + { + config_optics(zoomValue, focusValue, diaphragmValue, syncWithIntervalOptics); + } + } + else if (inputString_rpc.startsWith("/action:")) //Optics configuration + { + int* value = decode_values(inputString_rpc, 1); + #if DEBUG_M4 + RPC.print("Recibido action M4: "); + RPC.println(inputString_rpc); + for(int i=0; i<1; i++) RPC.println(value[i]); + #endif + isAction=value[0]; + if (isAction) + { + if (motorIsSpeedActive) config_speed_motor(4, motorDirection, motorSpeedValue); + else config_interval_motor(motorDirection, motorIntervalFrames, motorIntervalSeconds); + config_automatic_fade(shutterFadeFrames, shutterSyncWithInterval, shutterFadeInActive, shutterFadeOutActive); + } + else + { + secure_stop(motorDirection); + } + } + else if (inputString_rpc.startsWith("/sensors:")) //Optics configuration + { + int* value = decode_values(inputString_rpc, 1); + #if DEBUG_M4 + RPC.print("Recibido fps M4: "); + RPC.println(inputString_rpc); + for(int i=0; i<1; i++) RPC.println(value[i]); + #endif + if(value[0]) + RPC.println("/sensors:" + String(fps_read) + "," + String(analogRead(sensor_lineal_motor)) + "," + String(position_motor[1]) + "," + String(position_motor[2]) + "," + String(position_motor[3])); + //RPC.println("/sensors:" + String(fps_read) + "," + String(position_motor[0]) + "," + String(position_motor[1]) + "," + String(position_motor[2]) + "," + String(position_motor[3])); + //RPC.println(fps_read); + } + inputString_rpc = String(); + digitalWrite(LED_BUILTIN, HIGH); + } + else + inputString_rpc += c_rpc; + } + } + +void setup() { + //SCB_CleanDCache(); + RPC.begin(); + //delay(5000); + pinMode(sensor_fps, INPUT_PULLUP); + pinMode(Enable, OUTPUT); + pinMode(EN_M4, OUTPUT); + digitalWrite(EN_M4, HIGH); + analogWriteResolution(8); + digitalWrite(Enable, LOW); + sr.setAllLow(); // set all pins LOW + ini_motors(); + secure_stop(FORWARD); + attachInterrupt(digitalPinToInterrupt(sensor_fps), fps_count_state, RISING); + + #if PID_ENABLE + outMax = 255.0; // Límite máximo del controlador PID. + outMin = 128.0; // Límite mínimo del controlador PID. + + tmp = 5; // Tiempo de muestreo en milisegundos. + + kp = 10.0; // Constantes PID iniciales. Los valores son los adecuados para un encoder de 334 ppr, + ki = 3.5; // pero como el lector de encoder está diseñado como x4 equivale a uno de 1336 ppr. (ppr = pulsos por revolución.) + kd = 30.0; + + myPID.SetSampleTime(tmp); // Envía a la librería el tiempo de muestreo. + myPID.SetOutputLimits(outMin, outMax);// Límites máximo y mínimo; corresponde a Max.: 0=0V hasta 255=5V (PWMA), y Min.: 0=0V hasta -255=5V (PWMB). Ambos PWM se convertirán a la salida en valores absolutos, nunca negativos. + myPID.SetTunings(kp, ki, kd); // Constantes de sintonización. + myPID.SetMode(AUTOMATIC); // Habilita el control PID (por defecto). + Setpoint = 24; // Para evitar que haga cosas extrañas al inciarse, igualamos los dos valores para que comience estando el motor parado. + #endif + + #if DEBUG_M4 + RPC.println("M4 Inicializado."); + #endif +} + +void loop() +{ + #if PID_ENABLE + /*Input = (double)fps_temp; // Lectura del encoder óptico. El valor del contador se incrementa/decrementa a través de las interrupciones extrenas (pines 2 y 3). + if(myPID.Compute()) + analogWrite(EN_MOTOR[4], abs(Output)); // Por el primer pin sale la señal PWM. + */ + #endif + refresh_position_motors(); + refresh_interval_motors(); + RPCRead(); + if(force_stop) + { + //config_speed_motor(FPS_MOTOR, !motorDirection, MIN_SPEED); + //delay(20); + stop(FPS_MOTOR); + force_stop = false; + } +} \ No newline at end of file diff --git a/CraterLab_camera/include/main_m7.cpp b/CraterLab_camera/include/main_m7.cpp new file mode 100644 index 0000000..c4504f5 --- /dev/null +++ b/CraterLab_camera/include/main_m7.cpp @@ -0,0 +1,348 @@ +//#include +#include +#include +#include +#include "interface.html" +#include "constants.h" +#include + +#define DEBUG_M7 false +#define AP_MODE false + +// Inicializando RTOS +using namespace rtos; +Thread sensorThread; + +// Configuración de red WiFi +const char *ssid = "Analogue_Hyperlapse_Camera"; +const char *password = "CraterLab"; + +IPAddress ip(192, 168, 8, 4); +IPAddress remote_ip(192, 168, 8, 3); +IPAddress gateway(192, 168, 8, 1); +IPAddress subnet(255, 255, 255, 0); +IPAddress dns(192, 168, 8, 1); //primaryDNS + +// Crear el servidor en el puerto 80 +WiFiServer server(80); +// Crear conexion UDP para enviar datos +WiFiUDP Udp; +unsigned int remotePort = 2390; // local port to send +unsigned int localPort = 2392; // local port to read +char packetBuffer[255]; //buffer to hold incoming packet +char ReplyBuffer[] = "acknowledged"; // a string to send back + +// Motor +int motorSpeedValue = 25; +bool motorIsSpeedActive = false; +int motorIntervalFrames = 1; +int motorIntervalSeconds = 1; +bool motorIsIntervalActive = false; +int motorDirection = 1; + +// Shutter +int shutterFadePercent = 0; +int shutterFadeFrames = 50; +bool shutterSyncWithInterval = false; +bool shutterFadeInActive = false; +bool shutterFadeOutActive = false; + +// Óptica +int zoomValue = 50; +int focusValue = 50; +float diaphragmValue = 1.8; +bool syncWithIntervalOptics = false; + +// Dispositivo 360 +int x0Degrees = 0; +int x0Duration = 0; +int x1Degrees = 0; +int x1Duration = 0; +int y0Degrees = 0; +int y0Duration = 0; +bool syncWithInterval360 = false; + +//Sensores +float motorSpeedRead = 0; +float FadePercentRead = 0; +int zoomValueRead = 0; +int focusValueRead = 0; +float diaphragmValueRead = 0; +int x0DegreesRead = 0; +int x1DegreesRead = 0; +int y0DegreesRead = 0; + +int read_value[10]; +int* decode_values(String inputString, int num_dec) + { + String str = inputString.substring(inputString.lastIndexOf(":") + 1); + read_value[0] = str.substring(0, str.indexOf(',')).toInt(); + for(int i=1; i=500) + { + time_refresh_sensors = millis(); + RPC.println("/sensors:1"); + } + } + +void setup() +{ + Serial.begin(1000000); + RPC.begin(); //boots M4 + #if AP_MODE + int status = WL_IDLE_STATUS; + // Create open network. Change this line if you want to create an WEP network: + WiFi.config(ip, dns, gateway, subnet); + status = WiFi.beginAP(ssid, password); + if (status != WL_AP_LISTENING) { + Serial.println("Creating access point failed"); + // don't continue + while (true) + ; + } + #else + WiFi.config(ip, dns, gateway, subnet); + WiFi.begin(ssid, password); + while (WiFi.status() != WL_CONNECTED) + { + delay(1000); + Serial.print("."); + } + #endif + + Serial.println(); + Serial.println("Conectado a WiFi!"); + Serial.print("Dirección IP: "); + Serial.println(WiFi.localIP()); + // Enable Server + server.begin(); + // Enable UDP + Udp.begin(localPort); +} + +bool flag_send[10] = {false ,false ,false ,false ,false ,false ,false ,false ,false ,false}; + +void handlePostRequest(String body) { + // Parseamos el cuerpo del JSON + StaticJsonDocument<1000> doc; + deserializeJson(doc, body); + int save = true; + //DeserializationError error = deserializeJson(doc, body); + /*if (error) { + Serial.println("Error al parsear el JSON"); + return; + }*/ + + Serial.println("Procesando JSON..."); + String type = doc["type"]; + if ((type=="save_motor")||(type=="test_motor")) + { + Serial.println(type); + if (type=="save_motor") save = true; + else save = false; + + /*motorSpeedValue = doc["speedValue"]; + motorIsSpeedActive = doc["isSpeedActive"]; + motorIntervalFrames = doc["intervalFrames"]; + motorIntervalSeconds = doc["intervalSeconds"]; + motorIsIntervalActive = doc["isIntervalActive"]; + String Direction = doc["direction"];*/ + motorSpeedValue = doc["0"]; + motorIsSpeedActive = doc["1"]; + motorIntervalFrames = doc["2"]; + motorIntervalSeconds = doc["3"]; + motorIsIntervalActive = doc["4"]; + String Direction = doc["5"]; + if (Direction=="forward") motorDirection = FORWARD; + else if (Direction=="backward") motorDirection = BACKWARD; + if(motorIsSpeedActive) + { + RPC.println("/s_motor:" + String(FPS_MOTOR) + "," + String(motorDirection) + "," + String(motorSpeedValue) + "," + String(save)); + } + else if(motorIsIntervalActive) + { + RPC.println("/i_motor:" + String(FPS_MOTOR) + "," + String(motorDirection) + "," + String(motorIntervalFrames) + "," + String(motorIntervalSeconds) + "," + String(save)); + } + /*Clave: type, Valor: motor + Clave: speedValue, Valor: )25 + Clave: isSpeedActive, Valor: false + Clave: intervalFrames, Valor: 1 + Clave: intervalSeconds, Valor: 1 + Clave: isIntervalActive, Valor: false + Clave: direction, Valor: forward*/ + } + else if ((type=="test_shutter")||(type=="save_shutter") ) + { + Serial.println(type); + if (type=="save_shutter") save = true; + else save = false; + /*shutterFadePercent = doc["fadePercent"]; + shutterFadeFrames = doc["fadeFrames"]; + shutterSyncWithInterval = doc["syncWithInterval"]; + shutterFadeInActive = doc["fadeInActive"]; + shutterFadeOutActive = doc["fadeOutActive"];*/ + shutterFadePercent = doc["0"]; + shutterFadeFrames = doc["1"]; + shutterSyncWithInterval = doc["2"]; + shutterFadeInActive = doc["3"]; + shutterFadeOutActive = doc["4"]; + RPC.println("/fade:" + String(shutterFadePercent) + "," + String(shutterFadeFrames) + "," + String(shutterSyncWithInterval) + "," + String(shutterFadeInActive) + "," + String(shutterFadeOutActive) + "," + String(save)); + } + else if ((type=="test_optics")||(type=="save_optics")) + { + Serial.println(type); + if (type=="save_optics") save = true; + else save = false; + zoomValue = doc["zoomValue"]; + focusValue = doc["focusValue"]; + diaphragmValue = doc["diaphragmValue"]; + syncWithIntervalOptics = doc["syncWithInterval"]; + RPC.println("/optics:" + String(zoomValue) + "," + String(focusValue) + "," + String(diaphragmValue) + "," + String(syncWithIntervalOptics) + "," + String(save)); + } + else if (type=="accion") + { + Serial.println(type); + RPC.println("/action:" + String(1)); + Udp.beginPacket(remote_ip, remotePort); + Udp.println("/action:" + String(1)); + Udp.endPacket(); + } + else if (type=="corten") + { + Serial.println(type); + RPC.println("/action:" + String(0)); + Udp.beginPacket(remote_ip, remotePort); + Udp.println("/action:" + String(0)); + Udp.endPacket(); + } + else if (type=="stop") RPC.println("/s_motor:4," + String(motorDirection) + "," + String(0) + ", 0"); + else Serial.println("No reconocido"); +} + +unsigned long time_blink=millis(); +bool state = false; + +void loop() { + WiFiClient client = server.available(); + if (client) { + #if DEBUG_M7 + Serial.println("Nuevo cliente conectado"); + #endif + String request = ""; + bool isPostRequest = false; + + while (client.connected()) { + if (client.available()) { + char c = client.read(); + request += c; + + // Identificar si es una solicitud POST + if (request.indexOf("POST") >= 0) { + isPostRequest = true; + } + + // Si se encuentra el final de la solicitud + if (c == '\n' && request.endsWith("\r\n\r\n")) { + #if DEBUG_M7 + Serial.println("Solicitud recibida:"); + Serial.println(request); + #endif + + if (isPostRequest) { + String body = ""; + while (client.available()) { + body += (char)client.read(); + } + #if DEBUG_M7 + Serial.println("Cuerpo del mensaje recibido:"); + Serial.println(body); + #endif + // Llamamos a la función para procesar la petición POST + handlePostRequest(body); + // Respuesta al cliente + client.println("HTTP/1.1 200 OK"); + client.println("Content-type:text/plain"); + client.println(); + client.println("Datos enviados correctamente"); + } else if (request.indexOf("GET /sensors") >= 0) { // actualiza fps en interface + // Respuesta para la ruta /motorSpeed + client.println("HTTP/1.1 200 OK"); + client.println("Content-Type: application/json"); + client.println(); + String response = "{\"sensors\":[" + String(motorSpeedRead) + "," + String(FadePercentRead) + "]}"; + client.print(response); + } else { + // Respuesta para servir la interfaz HTML + client.println("HTTP/1.1 200 OK"); + client.println("Content-type:text/html"); + client.println(); + client.print(htmlTemplate); + } + break; + } + } + } + client.stop(); + #if DEBUG_M7 + Serial.println("Cliente desconectado"); + #endif + } + //Enviar datos a M4 + RPCRead(); + refresh_sensors(); +} \ No newline at end of file diff --git a/CraterLab_camera/lib/README b/CraterLab_camera/lib/README new file mode 100644 index 0000000..2593a33 --- /dev/null +++ b/CraterLab_camera/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/CraterLab_camera/platformio.ini b/CraterLab_camera/platformio.ini new file mode 100644 index 0000000..7899ba1 --- /dev/null +++ b/CraterLab_camera/platformio.ini @@ -0,0 +1,33 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; https://docs.platformio.org/page/projectconf.html + +[env:ARDUINO_GIGA_M7] +;platform = https://github.com/dberlin/platform-ststm32.git#develop +;platform = https://github.com/dberlin/platform-ststm32 +platform = ststm32 +board = giga_r1_m7 +framework = arduino +monitor_speed = 1000000 +;upload_port = COM12 +board_build.arduino.flash_layout = 75_25 ;50_50, 75_25, 100_0 +lib_deps = https://github.com/br3ttb/Arduino-PID-Library + bblanchon/ArduinoJson@^7.2.0 + + +[env:ARDUINO_GIGA_M4] +;platform = https://github.com/dberlin/platform-ststm32.git#develop +platform = ststm32 +board = giga_r1_m4 +framework = arduino +monitor_speed = 1000000 +;upload_port = COM12 +board_build.arduino.flash_layout = 75_25 ;50_50, 75_25, 100_0 +lib_deps = https://github.com/Simsso/ShiftRegister74HC595 + https://github.com/br3ttb/Arduino-PID-Library \ No newline at end of file diff --git a/CraterLab_camera/src/main.cpp b/CraterLab_camera/src/main.cpp new file mode 100644 index 0000000..55bdb43 --- /dev/null +++ b/CraterLab_camera/src/main.cpp @@ -0,0 +1,7 @@ +#if defined(ARDUINO_GIGA_M7) + #include +#elif defined(ARDUINO_GIGA_M4) + #include +#else + #include +#endif \ No newline at end of file diff --git a/CraterLab_camera/test/README b/CraterLab_camera/test/README new file mode 100644 index 0000000..9b1e87b --- /dev/null +++ b/CraterLab_camera/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Test Runner and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html diff --git a/README.md b/README.md new file mode 100644 index 0000000..d863d54 --- /dev/null +++ b/README.md @@ -0,0 +1 @@ +Primera version del codigo y diseño de Analogue Hyperlapse Camera. \ No newline at end of file