├── Adafruit-GFX-Library-master.zip ├── Adafruit_BusIO-master.zip ├── Adafruit_SSD1306-master.zip ├── Compact_WIFI_Controler ├── DB-CompactControl-6.01-Basic.tft ├── DB-CompactControl-6.01-Disc.tft ├── DB-CompactControl-6.01-En.tft ├── DB-CompactControl_ESP32_feather_v6.03.ino └── Readme ├── Copyright Licence ├── DB3 ├── DB3_PTZ_v6.06.ino ├── DB3_VISCA_Decoder_v6.00.ino └── Update ReadMe ├── DB_PanHead_Turntable └── DBTurntableESP32_v6.01.ino ├── DB_PanTilt_Balanced ├── DB_PanTilt_B_v6.01.ino ├── DB_PanTilt_B_v6.03Beta.ino └── ReadMe ├── DB_PanTilt_OT ├── DB_PanTilt_OT_v6.03.ino └── ReadMe ├── DB_Slider └── DBsliderESP32-v6.01.ino ├── Digital Bird PTZplus WIFI Control Quickstart V6.03.pdf ├── DigitalBird-Software Installation Guide .pdf ├── ESP32 Dev Board form factor.jpeg ├── Easy_Nextion_Library-DB.zip ├── FastAccelStepper-master_DB.zip ├── FastLED-master.zip ├── GOC ├── DB3_PTZ_v6.04-GOC.ino └── DB3_VISCA_Decoder_1.01.ino ├── Mini Jib └── DB_JIB_v6.01.ino ├── PTZplus_WIFI_Controller ├── DB-PTZplusESP32-v6.05.ino ├── Digital Bird PTZplus WIFI Control Quickstart V6.03.pdf ├── Nextion_PTZplusControl-6.03-Basic.tft ├── Nextion_PTZplusControl-6.03-Disc.tft ├── Nextion_PTZplusControl-6.03-En.tft └── ReadMe ├── README.md ├── arduino-AS5600-master.zip └── githold /Adafruit-GFX-Library-master.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Adafruit-GFX-Library-master.zip -------------------------------------------------------------------------------- /Adafruit_BusIO-master.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Adafruit_BusIO-master.zip -------------------------------------------------------------------------------- /Adafruit_SSD1306-master.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Adafruit_SSD1306-master.zip -------------------------------------------------------------------------------- /Compact_WIFI_Controler/DB-CompactControl-6.01-Basic.tft: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Compact_WIFI_Controler/DB-CompactControl-6.01-Basic.tft -------------------------------------------------------------------------------- /Compact_WIFI_Controler/DB-CompactControl-6.01-Disc.tft: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Compact_WIFI_Controler/DB-CompactControl-6.01-Disc.tft -------------------------------------------------------------------------------- /Compact_WIFI_Controler/DB-CompactControl-6.01-En.tft: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Compact_WIFI_Controler/DB-CompactControl-6.01-En.tft -------------------------------------------------------------------------------- /Compact_WIFI_Controler/DB-CompactControl_ESP32_feather_v6.03.ino: -------------------------------------------------------------------------------- 1 | ////////////////////////////////////////////////////////////////////////////////////////////////////////////// 2 | /*Digital Bird Compact WIFI controller part of the Digital Bird Camera Motion Control System Project 2023 3 | Version 6.03 4 | 5 | Update Notes v6.03: 23rd April 2024 6 | Fixed a bug where ease values were not being correctly updated 7 | Also fixes the same bug where shutter speeds for camera bulb mode in timlapse were not being respected. 8 | 9 | 10 | 11 | 12 | 13 | Copyright 2023 Colin Henderson Digital Bird Motion Control 14 | 15 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 16 | 17 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 18 | 19 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 20 | 21 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 22 | 23 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY 24 | AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 26 | IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | 28 | Thx! 29 | 30 | *///////////////////////////////////////////////////////////////////////////////////////////////////////////// 31 | 32 | 33 | #include 34 | #include 35 | #include 36 | #include 37 | 38 | #include 39 | #include 40 | #include 41 | 42 | Preferences SysMemory; 43 | 44 | /* 45 | ESP32 uses Hardware serial RX:16, TX:17 46 | Serial pins are defined in the ESPNexUpload.cpp file 47 | */ 48 | // 49 | 50 | 51 | 52 | //Variables 53 | int BD = 1; //Bounce / Return delay time in seconds 54 | int SLDL; //Leangth of slider rail in mm 55 | 56 | int PanS; //Pan joystick speed multiplier 57 | int TiltS; //Tilt joystick speed multiplier 58 | int TLY = 1; //Tally light on or off 0 or 1 59 | 60 | int Snd; 61 | int MSeqTime; 62 | int FPS = 10; 63 | long tiltS; 64 | long tiltA; 65 | long panS; 66 | long panA; 67 | long focusS; 68 | long focusA; 69 | long zoomS; 70 | long zoomA; 71 | long slidS; 72 | long slidA; 73 | long masterA; 74 | 75 | int stopMactive; 76 | int tilt_AVG; 77 | int pan_AVG; 78 | int foc_AVG; 79 | int zoom_AVG; 80 | int slid_AVG; 81 | 82 | String NexMenu; 83 | 84 | 85 | int ZoomJoyAccel; 86 | 87 | int sendjoy; 88 | int joypass; 89 | int usejoy; 90 | 91 | int PTZ_Cam = 5; //Current PTZ camera defaulted to 5 can be 1-4 92 | int PTZ_ID = 0; //PTZ Hardwae ID defaulted to 0 not used by PTZ functions 93 | int PTZ_Active; 94 | int PTZ_SaveP; 95 | int PTZ_Pose; 96 | int LM; //Focus/Zoom limits set 97 | // Phisical recoed button 98 | int RecordBut; //State of phisical record button on PTZ controler 99 | int Cam0_RecordBut; 100 | int Cam1_RecordBut; 101 | int Cam2_RecordBut; 102 | int Cam3_RecordBut; 103 | 104 | int lastRecordBut; //Last recorded state of button 105 | int lastCam1_RecordBut; 106 | int lastCam2_RecordBut; 107 | int lastCam3_RecordBut; 108 | 109 | int Tilt_J_Speed; 110 | int Pan_J_Speed; 111 | int Foc_J_Speed; 112 | int Zoom_J_Speed; 113 | int Slid_J_Speed; 114 | 115 | int SM; //stopMotion play true or false 116 | int SC; //stopMotion cancel true or false 117 | int SMC; //Stop Motion counter 118 | int SMC_last; 119 | 120 | float NexBatV; 121 | long Rail_Length = 500; //Edit this to use any rail length you require in mm 122 | long Max_Steps = 0; //Variable used to set the max number of steps for the given leangth of rail 123 | unsigned long previousMillis = 0; 124 | long set_speed = 0; 125 | long in_position = 0; // variable to hold IN position for slider 126 | long out_position = 0; // variable to hold OUT position for slider 127 | long travel_dist = 0; 128 | long step_speed = 0; // default travel speed between IN and OUT points 129 | int Crono_time = 10; 130 | int crono_hours = 0; 131 | int crono_minutes = 0; 132 | int crono_seconds = 10; 133 | String DBFirmwareVersion = "DBv6.03"; 134 | String nextion_message; // variable to hold received message for Nextion LCD 135 | int move_left = 0; // variable to detect move left on Nextion LCD 136 | int move_right = 0; // variable to confirm move right on Nextion LCD 137 | int start_cycle = 0; // variable to confirm start of travel between IN and OUT points 138 | long Home_position = 0; // Variable to st home position on slider 139 | int Ease_Value = 0; // Variable to collect Ease_Value from nextion screen value range 1-3 140 | int ease_time = 0; // Extra time allowed for ease in out calculation 141 | int move_finished = 1; // Used to check if move is completed 142 | long initial_homing = -1; // Used to Home Stepper at startup 143 | int Bounce = 0; 144 | int Tps = 0; 145 | int Tps_countdown = 0; 146 | int Tps_step_dist = 0; 147 | int TpsD = 1000; 148 | int Buttonset = 0; 149 | int timelapse_projected = 0; 150 | int getEncoder = 0; 151 | int InP = 0; 152 | int OutP = 0; 153 | int clrK; //Clear all keyframe memories back to 0 154 | int P1; //Sequencer button states 155 | int P2; 156 | int P3; 157 | int P4; 158 | int P5; 159 | int P6; 160 | 161 | 162 | 163 | int s1 = 50; 164 | int s2 = 50; 165 | int s3 = 50; 166 | int s4 = 0; 167 | int s5 = 0; 168 | int s6 = 0; 169 | int a1 = 0; 170 | int a2 = 0; 171 | int a3 = 0; 172 | int a4 = 0; 173 | int a5 = 0; 174 | int a6 = 0; 175 | int SE = 0; 176 | 177 | int TiltPanComand = 0; 178 | int playbuttoncounter = 1; 179 | String dataTx; 180 | String wifimessage; 181 | int PanTiltPlay; 182 | int PanTiltInPoint; 183 | int PanTiltOutPoint; 184 | int Nextion_Func; 185 | int Nextion_play; 186 | int But_Com; 187 | int TpsM; 188 | 189 | int incomingEz; 190 | int incomingBo; 191 | int incomingCro; 192 | int incomingFnc; 193 | int incomingTps; 194 | int incomingTpsD; 195 | int incomingPlay; 196 | long incomingIn; 197 | long incomingOut; 198 | int incomingBut; 199 | int incommingInP; 200 | int incommingOutP; 201 | int incommingTpsM; 202 | 203 | int Sld = 0; //Is the Slider present 1 or 0 204 | int PT; //Is the Pan Tilt present 1 0 0 205 | int TT; //Is the turntable present 1 or 0 206 | int JB; //Is the Jib present 1 or 0 207 | int mess; 208 | 209 | //VISCA setups 210 | int Pose; 211 | int ViscaComand; 212 | int number; 213 | int IP1 = 192; 214 | int IP2 = 168; 215 | int IP3 = 100; 216 | int IP4 = 100; 217 | int IPGW = 1; 218 | int UDP = 1259; 219 | int IPR; 220 | int LastViscaComand; 221 | int VPanSpeed; 222 | int VTiltSpeed; 223 | int VFocusSpeed; 224 | int VZoomSpeed; 225 | int VPoseNumber; 226 | int PP = 0; //pan angle = value=angle x 100 227 | int Tt = 80; //Tilt angle 228 | int ZZ = 0; //Zoom angle 229 | int FF = 0; //Focus angle 230 | //******************************************************************************************************************* 231 | //Change these valus depending on which pan tilt head you havebuilt over the top or balanced 232 | // These speed controls would be beter placed on rotary encoders one for each axis 233 | //int Tilt_J_Speed = 200; //Set this to 150 for the Balanced PT 200 for the Over the Top PT 234 | //int Pan_J_Speed = 4000; //Set this to 150 for the Balanced PT 4000 for the Over the Top PT 235 | //int foc_J_Speed = 4000; 236 | //int zoom_J_Speed = 4000; 237 | //int slid_J_Speed = 4000; 238 | //output for each axis requires two pices of information Speed and Accelorations this is 60 bits to many! 239 | 240 | 241 | //******************************************************************************************************************** 242 | 243 | 244 | //Structure example to send data 245 | //Must match the receiver structure 246 | //Structure to send WIFI data. Must match the receiver structure 247 | //Structure to send WIFI data. Must match the receiver structure 248 | 249 | //Structure to send WIFI data. Must match the receiver structure currently 136bytes of 250 max fo ESP-Now 250 | typedef struct struct_message { 251 | int Snd; //1= Controller 2=slider, 3=Pan Tilt 4=Turntable 5=Jib 252 | int But; //But_Com Nextion button press holder 253 | int Jb; //Joystick button state true or false 254 | //Joystick controler peramiters 255 | int Ts; //Axis speeds 256 | int Ps; 257 | int Fs; 258 | int Zs; 259 | int Ss; 260 | int Ma; //Master acceloration pot 261 | // PTZ peramiters 262 | int ID; //Hardware ID for PTZ 263 | int CA; //Camera selection for PTZ 264 | int SP; //PTZ_SaveP PTZ save pose 265 | int Pz; //PTZ_Pose PTZ current pose 266 | int Rc; //Record button state for PTZ 267 | int LM; //Focus/zoom limits set 268 | // stopMotion peramiters 269 | int SM; //stopMotion play true or false 270 | int SC; //stopMotion cancel 271 | int SMC; //Stop motion count 272 | 273 | int Ez; //Ease Value 274 | int Bo; //Number of bounces 275 | int TT; //Is the turntable present 1 or 0 276 | int PT; //Is the PanTilt 1 or 0 2 PanTilt Bounce trigger prevents cumulative speed errors 277 | int Sld; //Is the Slider present 1 or 0 278 | int JB; //Is the Jib present 1 or 0 279 | long In; //Slider In position in steps 280 | int P1; //Key button preses 281 | int P2; 282 | int P3; 283 | int P4; 284 | int P5; 285 | int P6; 286 | int s1; //Key Speeds 287 | int s2; 288 | int s3; 289 | int s4; 290 | int s5; 291 | int s6; 292 | // int a1; //Key Accelorations 293 | // int a2; 294 | // int a3; 295 | // int a4; 296 | // int a5; 297 | // int a6; 298 | int Cro; //Time in seconds of move 299 | //int Fnc; //Nection Function 300 | int Tps; //Timlapse frames required 301 | long Out; //Slider Out position in steps 302 | 303 | int InP; //Inpoint button press 304 | int clrK; //Tell all devices currently active to clear key memories value 1 or 0 305 | int OutP; //Out point button press 306 | int TpsD; //Timlapse Delay in seconds 307 | int TpsM; //Timlapse shutter time in seconds 308 | int Play; //Play button press 309 | 310 | int IPR; //Request for IP data 0-3 311 | int IP1; 312 | int IP2; 313 | int IP3; 314 | int IP4; 315 | int IPGW; 316 | int UDP; 317 | int TLY; 318 | int BD; 319 | //int mess; 320 | } struct_message; 321 | 322 | struct_message NextionValues; // Create a struct_message to Hold outgoing values 323 | struct_message incomingValues; // Create a struct_message to hold incoming values from TiltPan and Turntable 324 | 325 | int WIFIOUT[8]; //set up 5 element array for sendinf values to pantilt 326 | //*********************************Use thit TX RX for Feather bord 327 | #define RXD2 16 //Hardware Serial2 on ESP32 Dev (must also be a common earth between nextion and esp32)should be gpio 3 for lolin32 328 | #define TXD2 17 //Should be gpio 1 for Lolin32 if using Seril1 329 | //**********************************For LOLIN32 comment out the two lines above and uncomment the two lines bellow 330 | //#define RXD2 3 //Hardware Serial2 on ESP32 Dev (must also be a common earth between nextion and esp32)should be gpio 3 for lolin32 331 | //#define TXD2 1 //Should be gpio 1 for Lolin32 if using Seril1 332 | 333 | EasyNex myNex(Serial2); // Create an object of EasyNex class with the name < myNex > 334 | #define Nextion_Dim_Time 120 335 | hw_timer_t * timer = NULL; 336 | 337 | 338 | void IRAM_ATTR Nextion_Dim() { 339 | String dims = "dims=" + String(5); // set display brightness to 100% 340 | myNex.writeStr(dims.c_str()); 341 | 342 | } 343 | void Nextion_Wake() { 344 | String dims = "dims=" + String(100); // set display brightness to 100% 345 | myNex.writeStr(dims.c_str()); 346 | } 347 | 348 | //Joystick control 349 | const int panS_PIN = 0; // Pan Joy 350 | const int tiltS_PIN = 0; // Tilt Joy 351 | const int slidS_PIN = 0; // Slider joy 352 | const int focusS_PIN = 0; // Focus joy 353 | const int zoomS_PIN = 0; // Zoom joy 354 | const int masterA_PIN = 0; // Master pot 355 | const int NexBat = 35; //Battery monitoring pin 356 | //PTZ Play button 357 | #define CAM 0 // Pin Gpio 4 Camera trigger 358 | #define LED 0 // Pin forplay LED 359 | 360 | byte lastLEDstate = LOW; 361 | byte ledState = LOW; 362 | //unsigned long debounceDuration = 50; // millis 363 | unsigned long prevTime = 0; 364 | 365 | //Joystick button 366 | #define JBT 0 //Joystick button 367 | 368 | 369 | 370 | 371 | 372 | void setup() { 373 | Serial.begin(115200); 374 | Serial2.begin(115200, SERIAL_8N1, RXD2, TXD2); 375 | Serial.println("\nRunning DigitalBird Nextion ESP32 controler\n"); 376 | 377 | //Start Nextion Dim Timer 378 | timer = timerBegin(0, 80, true); // timer 0, MWDT clock period = 12.5 ns * TIMGn_Tx_WDT_CLK_PRESCALE -> 12.5 ns * 80 -> 1000 ns = 1 us, countUp 379 | timerAttachInterrupt(timer, &Nextion_Dim, true); // edge (not level) triggered 380 | timerAlarmWrite(timer, (Nextion_Dim_Time * 1000000), true); // 1000000 * 1 us = 1 s, autoreload true 381 | timerAlarmEnable(timer); // enable 382 | 383 | //**********************Prepair Nextion***********************************// 384 | String dims = "dims=" + String(100); // set display brightness to 100% 385 | myNex.writeStr(dims.c_str()); 386 | 387 | 388 | myNex.writeStr("t9.txt", String(DBFirmwareVersion)); 389 | delay(100); 390 | myNex.writeStr("t2.txt", "10"); //set seconds deay at 2 391 | 392 | //********************Setup Radio**********************************// 393 | WiFi.mode(WIFI_STA); 394 | 395 | Serial.println("\nmacAdress is:\n"); 396 | Serial.print(WiFi.macAddress()); 397 | WiFi.disconnect(); 398 | 399 | //******************Setup ESP_now*************************** 400 | if (esp_now_init() == ESP_OK) { 401 | Serial.println("ESPNow Init Sucess"); 402 | esp_now_register_recv_cb(receiveCallback); 403 | esp_now_register_send_cb(sentCallback); 404 | } 405 | else 406 | { Serial.println("ESPNow Init Failed"); 407 | delay(3000); 408 | ESP.restart(); 409 | } 410 | 411 | 412 | //pinMode(NexBat, INPUT); 413 | 414 | NexBatV = analogRead(NexBat); 415 | NexBatV = ((NexBatV / 4095) * 2) * 3.3; 416 | 417 | pinMode(JBT, INPUT_PULLUP); //Joystick button 418 | 419 | 420 | pinMode(CAM, INPUT_PULLUP); //Camera switch pulled high 421 | pinMode(LED, OUTPUT); 422 | InitialValues(); //onboard Joystick calobration 423 | 424 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 425 | 426 | 427 | pinMode(masterA_PIN, INPUT); 428 | 429 | 430 | String NexMenu = myNex.readStr("menu.txt"); 431 | Serial.printf("\nNextion Menu is currently %d \n", NexMenu.toInt()); 432 | 433 | 434 | } 435 | 436 | 437 | 438 | 439 | 440 | 441 | 442 | 443 | void loop() { 444 | 445 | NexBatV = analogRead(NexBat); 446 | NexBatV = ((NexBatV / 4095) * 2) * 3.3; 447 | // if (PTZ_Active || usejoy) { 448 | // ReadAnalog(); //Joystick setup 449 | // } 450 | 451 | //*************************************Joystick top button press Function******************************************* 452 | // if (digitalRead(JBT) == LOW) { 453 | // long unsigned int currTime = millis(); 454 | // if (currTime - prevTime > 50) { 455 | // if (usejoy) { //If usejoy is on 456 | // myNex.writeNum("b0.pic", 43); //Turn it off 457 | // usejoy = 0; 458 | // } else { //else turn it on 459 | // myNex.writeNum("b0.pic", 44); 460 | // usejoy = 1; 461 | // } 462 | // 463 | // prevTime = currTime; 464 | // delay(200); 465 | // } 466 | // } 467 | 468 | //*************************************PTZ Record button log******************************************* 469 | // if (digitalRead(CAM) == LOW) { 470 | // long unsigned int currTime = millis(); 471 | // if (currTime - prevTime > 50) 472 | // digitalWrite(LED, !digitalRead(LED)); 473 | // prevTime = currTime; 474 | // if (digitalRead(LED) == LOW) { 475 | // 476 | // switch (PTZ_Cam) { 477 | // case 1: 478 | // Cam1_RecordBut = 0; 479 | // break; 480 | // case 2: 481 | // Cam2_RecordBut = 0; 482 | // break; 483 | // case 3: 484 | // Cam3_RecordBut = 0; 485 | // break; 486 | // } 487 | // RecordBut = 0; //For any other Play command 488 | // } else { 489 | // //Serial.println("Play ON"); //Turn on the camera 490 | // switch (PTZ_Cam) { 491 | // case 1: 492 | // Cam1_RecordBut = 1; 493 | // break; 494 | // case 2: 495 | // Cam2_RecordBut = 1; 496 | // break; 497 | // case 3: 498 | // Cam3_RecordBut = 1; 499 | // break; 500 | // } 501 | // RecordBut = 1; //For any other Play command 502 | // } 503 | // } else { //Button not in depressed state ON 504 | // 505 | // if (PTZ_Active == 0 && (RecordBut != lastRecordBut)) { //If PTZ is not active 506 | // String NexMenu = myNex.readStr("menu.txt"); 507 | // switch (NexMenu.toInt()) { 508 | // case 1: //Nextion menu is home 509 | // But_Com = 1; //If we are in the home menu Send the home screen play command 510 | // lastRecordBut = RecordBut; 511 | // trigger9(); //Home Play button press 512 | // break; 513 | // case 2: //Nextion menu is sequencer 514 | // Nextion_play = 2; 515 | // SendNextionValues(); 516 | // delay(200); 517 | // Nextion_play = 0; //Reset the button 518 | // lastRecordBut = RecordBut; 519 | // myNex.writeNum("b5.pic", 7); //Turn play red 520 | // break; 521 | // case 6: //Nextion menu is stopmotion 522 | // trigger39(); 523 | // // SM = 1; 524 | // // SendNextionValues(); 525 | // // delay(200); 526 | // // SM = 0; 527 | // lastRecordBut = RecordBut; 528 | // myNex.writeNum("Play.pic", 7); //Turn play red 529 | // break; 530 | // } 531 | // } 532 | // 533 | // if (PTZ_Active) { //If PTZ is active 534 | // switch (PTZ_Cam) { 535 | // case 1: 536 | // if (Cam1_RecordBut != lastCam1_RecordBut) { 537 | // SendNextionValues(); 538 | // lastCam1_RecordBut = Cam1_RecordBut; 539 | // } 540 | // break; 541 | // case 2: 542 | // if (Cam2_RecordBut != lastCam2_RecordBut) { 543 | // SendNextionValues(); 544 | // lastCam2_RecordBut = Cam2_RecordBut; 545 | // } 546 | // break; 547 | // case 3: 548 | // if (Cam3_RecordBut != lastCam3_RecordBut) { 549 | // SendNextionValues(); 550 | // lastCam3_RecordBut = Cam3_RecordBut; 551 | // } 552 | // break; 553 | // } 554 | // } 555 | // } 556 | 557 | 558 | //*************************************Listen for Nextion LCD comands******************************************* 559 | myNex.NextionListen(); // nextion_message.NextionListen(); //check for message from Nextion touchscreen 560 | 561 | 562 | //*********************StopMotion Canceled*********************************** 563 | if (SC == 1) { 564 | myNex.writeStr("SMC_counter.txt", "CANCEL"); //Move canceled 565 | delay(1000); 566 | myNex.writeStr("SMC_counter.txt", String(Tps)); //Send counter back to start 567 | delay(20); 568 | SMC = Tps; 569 | SC = 0; 570 | SendNextionValues(); 571 | delay(20); 572 | } 573 | //*************************************Listen for IPR request reply***************************************** 574 | //Serial.printf("IPR is set to %d\n", IPR); 575 | if (IPR == 2) { //Process the IP data from the device and pass it on to the Nextion 576 | Serial.print(IPR); 577 | delay(500); 578 | myNex.writeStr("IP1.txt", String(IP1)); 579 | delay(20); 580 | myNex.writeStr("IP2.txt", String(IP2)); 581 | delay(20); 582 | myNex.writeStr("IP3.txt", String(IP3)); 583 | delay(20); 584 | myNex.writeStr("IP4.txt", String(IP4)); 585 | delay(20); 586 | myNex.writeStr("IPGW.txt", String(IPGW)); 587 | delay(20); 588 | myNex.writeStr("UDP.txt", String(UDP)); 589 | delay(20); 590 | IPR = 0; 591 | } else { 592 | //Serial.println(IPR); 593 | } 594 | //*************************************Listen for slave device button comands***************************************** 595 | if (But_Com != 0) { //If a button comand has been received from a slave 596 | 597 | switch (But_Com) { 598 | 599 | case 1: //Play request from slave 600 | Nextion_play = 1; 601 | But_Com = 0; //Reset the Slave button request 602 | SendNextionValues(); //Send out the play command 603 | Nextion_play = 0; //Reset play 604 | //digitalWrite(LED, LOW); 605 | lastRecordBut = 0; 606 | RecordBut = 0; 607 | break; 608 | case 2: //InPoint set request from slave 609 | trigger7(); //Same as if pressed on nextion 610 | But_Com = 0; 611 | break; 612 | case 3: //OutPoint set request from slave 613 | trigger8(); //Same as if pressed on nextion 614 | But_Com = 0; 615 | break; 616 | case 4: 617 | //delay(5); 618 | myNex.writeNum("rewind.val", 0); //zero the nextion timer 619 | delay(20); 620 | myNex.writeNum("TimerStop.val", 1); // timer Start 621 | But_Com = 0; 622 | break; 623 | case 5: 624 | myNex.writeNum("TimerStop.val", 0); //Stop nextion timer 625 | delay(100); 626 | digitalWrite(LED, LOW); //Turn off the button LED 627 | myNex.writeNum("Play.pic", 8); //Turn play yellow 628 | delay(50); 629 | myNex.writeNum("b5.pic", 8); //Turn play yellow 630 | But_Com = 0; 631 | delay(1000); 632 | case 6: 633 | delay(5); 634 | myNex.writeStr("bounce.txt", String(Bounce)); //update Bounce counter main 635 | delay(5); 636 | myNex.writeStr("Bounce.txt", String(Bounce)); //update Bounce counter SEQ 637 | But_Com = 0; 638 | break; 639 | case 7: 640 | delay(5); 641 | myNex.writeStr("tlps.txt", String(Tps)); //update timlapse counter 642 | delay(5); 643 | if (Tps == 0) { 644 | crono_seconds = 10; 645 | Crono_time = 10; 646 | SendNextionValues(); 647 | delay(5); 648 | myNex.writeStr("sec.txt", String(crono_seconds)); 649 | But_Com = 0; 650 | } 651 | But_Com = 0; 652 | break; 653 | case 8: //Stop Motion counter update 654 | delay(30); 655 | if (SMC != 0) { 656 | myNex.writeStr("SMC_counter.txt", String(SMC)); //Update Nextion frame counter 657 | delay(50); 658 | //digitalWrite(LED, LOW); //Turn OFF the button LED 659 | myNex.writeNum("Play.pic", 8); //Turn play yellow 660 | delay(50); 661 | } else { 662 | //digitalWrite(LED, LOW); //Turn OFF the button LED 663 | myNex.writeStr("SMC_counter.txt", "Complete"); //Update Nextion frame counter 664 | delay(10); 665 | myNex.writeStr("SMC_counter.txt", String(Tps)); //Send counter back to start 666 | delay(20); 667 | } 668 | But_Com = 0; 669 | break; 670 | } 671 | } 672 | 673 | 674 | } //end loop 675 | 676 | 677 | 678 | 679 | //***************************Nextion Button Press Functions*****************************// 680 | 681 | //***************************Nextion Button Press Functions*****************************// 682 | 683 | void trigger1() { //Nextion m0 Hours 684 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 685 | Nextion_Wake(); 686 | Nextion_Func = 0; 687 | SendNextionValues(); 688 | UpdateSEQ(); 689 | } 690 | void trigger2() { //Nextion m1 Min 691 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 692 | Nextion_Wake(); 693 | Nextion_Func = 1; 694 | SendNextionValues(); 695 | } 696 | 697 | void trigger3() { // Nextion m2 Sec 698 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 699 | Nextion_Wake(); 700 | Nextion_Func = 2; 701 | SendNextionValues(); 702 | } 703 | 704 | void trigger4() { //Nextion m3 Ease 705 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 706 | Nextion_Wake(); 707 | Nextion_Func = 3; 708 | SendNextionValues(); 709 | } 710 | 711 | void trigger5() { //Nextion m4 Bounce 712 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 713 | Nextion_Wake(); 714 | Nextion_Func = 4; 715 | SendNextionValues(); 716 | } 717 | 718 | void trigger6() { //Nextion m5 Tps 719 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 720 | Nextion_Func = 5; 721 | SendNextionValues(); 722 | } 723 | 724 | void trigger7() { //Nextion m6 InPoint 725 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 726 | Nextion_Wake(); 727 | Nextion_Func = 6; 728 | ++InP; 729 | switch (InP) { 730 | case 1: //First Press: Request a new InPoint 731 | SendNextionValues(); 732 | break; 733 | case 2: //Second Press: Record position 734 | SendNextionValues(); 735 | InP = 0; //Reset InPoint press back to 0 736 | break; 737 | } 738 | } 739 | 740 | void trigger8() { // Nextion m7 OutPoint 741 | 742 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 743 | Nextion_Wake(); 744 | Nextion_Func = 7; 745 | ++OutP; 746 | switch (OutP) { 747 | case 1: //First Press: Request a new InPoint 748 | SendNextionValues(); 749 | break; 750 | case 2: //Second Press: Record position 751 | SendNextionValues(); 752 | OutP = 0; //Reset InPoint press back to 0 753 | break; 754 | } 755 | } 756 | 757 | void trigger9() { // Nextion m7 Play 758 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 759 | if (stopMactive == 1) { 760 | stopMactive = 0; 761 | myNex.writeStr("tlps.txt", "0"); 762 | Tps = 0; 763 | } 764 | Nextion_Wake(); 765 | Nextion_play = 1; 766 | SendNextionValues(); 767 | digitalWrite(LED, HIGH); //Turn on LED 768 | myNex.writeNum("Play.pic", 7); //Turn play red 769 | delay(200); 770 | Nextion_play = 0; //Reset the button 771 | } 772 | 773 | 774 | void trigger10() { // Nextion Up arrow 0A hex 775 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 776 | Nextion_Wake(); 777 | switch (Nextion_Func) { 778 | 779 | case 0: // + time Hours on nextion 780 | if (crono_hours >= 0 && crono_hours <= 23) { //limit hours that can be set between 0 & 24 781 | crono_hours = crono_hours + 1; // increase by 1 782 | myNex.writeStr("hours.txt", String(crono_hours)); 783 | Crono_time = ((crono_hours * 3600) + (crono_minutes * 60) + crono_seconds); 784 | } 785 | break; 786 | case 1: // + time Minuts on nextion 787 | if (crono_minutes >= 0 && crono_hours <= 59) { //limit Minuits that can be set between 0 & 60 788 | crono_minutes = crono_minutes + 1; // increase by 1 789 | myNex.writeStr("min.txt", String(crono_minutes)); 790 | Crono_time = ((crono_hours * 3600) + (crono_minutes * 60) + crono_seconds); 791 | } 792 | break; 793 | case 2: // + time Seconds on nextion 794 | if (crono_seconds >= 0 && crono_seconds <= 59) { //limit seconds that can be set between 0 & 60 795 | crono_seconds = crono_seconds + 1; // increase by 1 796 | myNex.writeStr("sec.txt", String(crono_seconds)); 797 | Crono_time = ((crono_hours * 3600) + (crono_minutes * 60) + crono_seconds); 798 | } 799 | if (Tps > 0) { 800 | TpsD = (crono_seconds * 1000); 801 | } 802 | break; 803 | case 3: // + Ease value 804 | if (Ease_Value >= 0 && Ease_Value <= 2) { //limit Ease that can be set between 0 & 3 805 | Ease_Value = Ease_Value + 1; // increase by 1 806 | myNex.writeStr("ease.txt", String(Ease_Value)); 807 | } 808 | break; 809 | case 4: //+Bounce Value Func 810 | if (Bounce <= 10 && Bounce != 500) { 811 | Bounce = Bounce + 1; // increase by 1 812 | myNex.writeStr("bounce.txt", String(Bounce)); // display value in t4 Bounce box on Nextion 813 | myNex.writeStr("bounce.txt", String(Bounce)); 814 | } else { 815 | Bounce = 500; //If greater than ten assume infinity 500 bring it down again to 10 816 | myNex.writeStr("bounce.txt", "Inf"); 817 | myNex.writeStr("bounce.txt", "Inf"); 818 | } 819 | break; 820 | case 5: // + Tps on nextion 821 | if (Tps >= 0 ) { 822 | Tps = Tps + 25; // increase Tps by 25 823 | myNex.writeStr("tlps.txt", String(Tps)); // display seconds in t2 box on Nextion 824 | if (Tps != 0) { 825 | timelapse_projected = (5 + (Tps * 2.501)); 826 | crono_seconds = 2; 827 | myNex.writeStr("sec.txt", "2"); //set seconds deay at 2 828 | myNex.writeStr("min.txt", "0"); //set min at 0 829 | myNex.writeStr("hours.txt", "0"); //set hours at 0 830 | myNex.writeStr("t8.txt", String(timelapse_projected)); 831 | } 832 | } 833 | break; 834 | case 20: 835 | MSeqTime++; //Add a second to SequenceTime 836 | myNex.writeStr("SeqTime.txt", String(MSeqTime)); //Update Nextion 837 | Tps = (MSeqTime * FPS); 838 | myNex.writeStr("SMC_counter.txt", String(Tps)); 839 | delay(20); 840 | break; 841 | case 21: 842 | TpsD = (TpsD + 1000); 843 | myNex.writeStr("shutterT.txt", String(TpsD / 1000)); //Update Nextion 844 | break; 845 | case 22: 846 | FPS++; 847 | myNex.writeStr("fps.txt", String(FPS)); //Motion control FPS add 848 | Tps = (MSeqTime * FPS); 849 | myNex.writeStr("SMC_counter.txt", String(Tps)); 850 | delay(20); 851 | break; 852 | case 23: // + time Minuts on nextion 853 | // if (PanS >= 0 && PanS <= 5) { //limit Minuits that can be set between 0 & 60 854 | // PanS = PanS + 1; // increase by 1 855 | // myNex.writeStr("PanS.txt", String(PanS)); 856 | // } 857 | break; 858 | case 24: // + time Minuts on nextion 859 | // if (TiltS >= 0 && TiltS <= 5) { //limit Minuits that can be set between 0 & 60 860 | // TiltS = TiltS + 1; // increase by 1 861 | // myNex.writeStr("TiltS.txt", String(TiltS)); 862 | // } 863 | break; 864 | } 865 | SC = 1; 866 | PanTiltPlay = 1; 867 | SendNextionValues(); 868 | SC = 0; 869 | } 870 | 871 | void trigger11() { // Nextion Down arrow 872 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 873 | Nextion_Wake(); 874 | switch (Nextion_Func) { 875 | 876 | case 0: // + time Hours on nextion 877 | if (crono_hours >= 1) { //limit hours that can be set between 0 & 24 878 | crono_hours = crono_hours - 1; // increase by 1 879 | myNex.writeStr("hours.txt", String(crono_hours)); 880 | Crono_time = ((crono_hours * 3600) + (crono_minutes * 60) + crono_seconds); 881 | } 882 | break; 883 | case 1: // - time Minuts on nextion 884 | if (crono_minutes >= 1) { //limit Minuits that can be set between 0 & 60 885 | crono_minutes = crono_minutes - 1; 886 | myNex.writeStr("min.txt", String(crono_minutes)); 887 | Crono_time = ((crono_hours * 3600) + (crono_minutes * 60) + crono_seconds); 888 | } 889 | break; 890 | case 2: // + time Seconds on nextion 891 | if (crono_seconds >= 1) { //limit seconds that can be set between 0 & 60 892 | crono_seconds = crono_seconds - 1; 893 | myNex.writeStr("sec.txt", String(crono_seconds)); 894 | Crono_time = ((crono_hours * 3600) + (crono_minutes * 60) + crono_seconds); 895 | } 896 | break; 897 | case 3: // + Ease value 898 | if (Ease_Value >= 1) { //limit Ease that can be set between 0 & 3 899 | Ease_Value = Ease_Value - 1; // increase by 1 900 | myNex.writeStr("ease.txt", String(Ease_Value)); 901 | } 902 | break; 903 | case 4: //-Bounce Value Func 904 | if (Bounce <= 10 && Bounce != 500 && Bounce != 0) { 905 | Bounce = Bounce - 1; 906 | myNex.writeStr("bounce.txt", String(Bounce)); // display value in t4 Bounce box on Nextion 907 | myNex.writeStr("bounce.txt", String(Bounce)); 908 | } else { 909 | Bounce = 10; //If greater than ten assume infinity 500 bring it down again to 10 910 | myNex.writeStr("bounce.txt", String(Bounce)); 911 | myNex.writeStr("bounce.txt", String(Bounce)); 912 | } 913 | break; 914 | case 5: // + Tps on nextion 915 | if (Tps > 0 ) { 916 | Tps = Tps - 25; // increase Tps by 25 917 | myNex.writeStr("tlps.txt", String(Tps)); // display seconds in t2 box on Nextion 918 | if (Tps == 0) { 919 | timelapse_projected = 0; 920 | crono_seconds = 10; 921 | Crono_time = 10; 922 | myNex.writeStr("t8.txt", String(timelapse_projected)); 923 | myNex.writeStr("sec.txt", "10"); //set seconds deay at 2 924 | myNex.writeStr("min.txt", "0"); //set min at 0 925 | myNex.writeStr("hours.txt", "0"); //set hours at 0 926 | 927 | } 928 | } 929 | break; 930 | 931 | case 20: 932 | if (MSeqTime >= 1) { 933 | MSeqTime = (MSeqTime - 1); //Subtract a second from SequenceTime 934 | myNex.writeStr("SeqTime.txt", String(MSeqTime)); //Update Nextion 935 | Tps = (MSeqTime * FPS); 936 | myNex.writeStr("SMC_counter.txt", String(Tps)); 937 | delay(20); 938 | 939 | } 940 | break; 941 | 942 | 943 | 944 | 945 | 946 | 947 | case 21: 948 | if (TpsD >= 1000) { 949 | TpsD = (TpsD - 1000); 950 | myNex.writeStr("shutterT.txt", String(TpsD / 1000)); //Update Nextion 951 | } 952 | break; 953 | case 22: 954 | FPS = FPS - 1; 955 | myNex.writeStr("fps.txt", String(FPS)); //Motion control FPS add 956 | Tps = (MSeqTime * FPS); 957 | myNex.writeStr("SMC_counter.txt", String(Tps)); 958 | delay(20); 959 | break; 960 | 961 | case 23: // + time Minuts on nextion 962 | // if (PanS >= 1) { //limit Minuits that can be set between 0 & 60 963 | // PanS = PanS - 1; // increase by 1 964 | // myNex.writeStr("PanS.txt", String(PanS)); 965 | // } 966 | break; 967 | case 24: // + time Minuts on nextion 968 | // if (TiltS >= 1) { //limit Minuits that can be set between 0 & 60 969 | // TiltS = TiltS - 1; // increase by 1 970 | // myNex.writeStr("TiltS.txt", String(TiltS)); 971 | // } 972 | break; 973 | 974 | case 25: 975 | //IP adress 1 976 | IP1 = IP1 - 1; // Reduce by 1 for down arrow 977 | myNex.writeStr("IP1.txt", String(IP1)); 978 | delay(20); 979 | break; 980 | case 26: 981 | //IP adress 1 982 | IP2 = IP2 - 1; // Reduce by 1 for down arrow 983 | myNex.writeStr("IP2.txt", String(IP2)); 984 | delay(20); 985 | break; 986 | case 27: 987 | //IP adress 1 988 | IP3 = IP3 - 1; // Reduce by 1 for down arrow 989 | myNex.writeStr("IP3.txt", String(IP3)); 990 | delay(20); 991 | break; 992 | case 28: 993 | //IP adress 1 994 | IP4 = IP4 - 1; // Reduce by 1 for down arrow 995 | myNex.writeStr("IP4.txt", String(IP4)); 996 | delay(20); 997 | break; 998 | 999 | 1000 | case 29: 1001 | if (UDP == 5678) { //IP adress 1 1002 | UDP = 1259; // Reduce by 1 for down arrow 1003 | myNex.writeStr("UDP.txt", String(UDP)); 1004 | } 1005 | delay(20); 1006 | break; 1007 | } 1008 | SC = 1; 1009 | PanTiltPlay = 1; 1010 | SendNextionValues(); 1011 | SC = 0; 1012 | } 1013 | 1014 | //********************************************sequencer************************************************************ 1015 | void trigger12() { //Nextion K1 Set 1016 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1017 | Nextion_Wake(); 1018 | Nextion_Func = 12; 1019 | ++P1; 1020 | switch (P1) { 1021 | case 1: //First Press: Request a new InPoint 1022 | SendNextionValues(); 1023 | break; 1024 | case 2: //Second Press: Record position 1025 | SendNextionValues(); 1026 | P1 = 0; //Reset InPoint press back to 0 1027 | break; 1028 | } 1029 | } 1030 | void trigger13() { //Nextion K2 Set 1031 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1032 | Nextion_Wake(); 1033 | Nextion_Func = 13; 1034 | ++P2; 1035 | switch (P2) { 1036 | case 1: //First Press: Request a new InPoint 1037 | SendNextionValues(); 1038 | break; 1039 | case 2: //Second Press: Record position 1040 | SendNextionValues(); 1041 | P2 = 0; //Reset InPoint press back to 0 1042 | break; 1043 | } 1044 | } 1045 | void trigger14() { //Nextion K3 Set 1046 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1047 | Nextion_Wake(); 1048 | Nextion_Func = 14; 1049 | ++P3; 1050 | switch (P3) { 1051 | case 1: //First Press: Request a new InPoint 1052 | SendNextionValues(); 1053 | break; 1054 | case 2: //Second Press: Record position 1055 | SendNextionValues(); 1056 | P3 = 0; //Reset InPoint press back to 0 1057 | break; 1058 | } 1059 | } 1060 | void trigger15() { //Nextion K4 Set 1061 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1062 | Nextion_Wake(); 1063 | Nextion_Func = 15; 1064 | ++P4; 1065 | switch (P4) { 1066 | case 1: //First Press: Request a new InPoint 1067 | SendNextionValues(); 1068 | break; 1069 | case 2: //Second Press: Record position 1070 | SendNextionValues(); 1071 | P4 = 0; //Reset InPoint press back to 0 1072 | break; 1073 | } 1074 | } 1075 | void trigger16() { //Nextion K5 Set 1076 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1077 | Nextion_Wake(); 1078 | Nextion_Func = 16; 1079 | ++P5; 1080 | switch (P5) { 1081 | case 1: //First Press: Request a new InPoint 1082 | SendNextionValues(); 1083 | break; 1084 | case 2: //Second Press: Record position 1085 | SendNextionValues(); 1086 | P5 = 0; //Reset InPoint press back to 0 1087 | break; 1088 | } 1089 | } 1090 | void trigger17() { //Nextion K6 Set 1091 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1092 | Nextion_Wake(); 1093 | Nextion_Func = 17; 1094 | ++P6; 1095 | switch (P6) { 1096 | case 1: //First Press: Request a new InPoint 1097 | SendNextionValues(); 1098 | break; 1099 | case 2: //Second Press: Record position 1100 | SendNextionValues(); 1101 | P6 = 0; //Reset InPoint press back to 0 1102 | break; 1103 | } 1104 | } 1105 | void trigger18() { //Nextion Clear key 1106 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1107 | Nextion_Wake(); 1108 | Nextion_Func = 18; 1109 | String k4String = myNex.readStr("k4t.txt"); 1110 | if (k4String.toInt() == 0) { 1111 | s4 = 0; 1112 | s5 = 0; 1113 | s6 = 0; 1114 | P4 = 0; 1115 | P5 = 0; 1116 | P6 = 0; 1117 | SendNextionValues(); 1118 | } else { 1119 | String k5String = myNex.readStr("k5t.txt"); 1120 | if (k5String.toInt() == 0) { 1121 | s5 = 0; 1122 | s6 = 0; 1123 | P5 = 0; 1124 | P6 = 0; 1125 | SendNextionValues(); 1126 | } 1127 | else { 1128 | String k6String = myNex.readStr("k5t.txt"); 1129 | if (k6String.toInt() == 0) { 1130 | s6 = 0; 1131 | P6 = 0; 1132 | SendNextionValues(); 1133 | } 1134 | } 1135 | } 1136 | } 1137 | void trigger19() { //Nextion sequencer play 1138 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1139 | Nextion_Wake(); 1140 | Nextion_Func = 19; 1141 | Nextion_play = 2; 1142 | SendNextionValues(); 1143 | delay(200); 1144 | digitalWrite(LED, HIGH); //Turn on LED 1145 | myNex.writeNum("b5.pic", 7); //Turn play red 1146 | Nextion_play = 0; //Reset the button 1147 | } 1148 | 1149 | void trigger20() { // Sequencer Up arrow 1150 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1151 | Nextion_Wake(); 1152 | 1153 | switch (Nextion_Func) { 1154 | case 4: //+Bounce Value Func 1155 | if (Bounce <= 10 && Bounce != 500) { 1156 | Bounce = Bounce + 1; // increase by 1 1157 | myNex.writeStr("t4.txt", String(Bounce)); // display value in t4 Bounce box on Nextion 1158 | myNex.writeStr("Bounce.txt", String(Bounce)); 1159 | } else { 1160 | Bounce = 500; //If greater than ten assume infinity 500 bring it down again to 10 1161 | myNex.writeStr("t4.txt", "Inf"); 1162 | myNex.writeStr("Bounce.txt", "Inf"); 1163 | } 1164 | break; 1165 | case 12: //K1 Set 1166 | if (SE == 0) { //If speed selected 1167 | if (s1 <= 95) { 1168 | s1 = s1 + 5; 1169 | myNex.writeStr("k1t.txt", String(s1)); 1170 | } 1171 | } else { 1172 | if (a1 <= 2) { 1173 | a1 = a1 + 1; 1174 | myNex.writeStr("a1.txt", String(a1)); 1175 | } 1176 | } 1177 | 1178 | break; 1179 | case 13: //K2 Set 1180 | if (SE == 0) { //If speed selected 1181 | if (s2 <= 95) { 1182 | s2 = s2 + 5; 1183 | myNex.writeStr("k2t.txt", String(s2)); 1184 | } 1185 | } else { 1186 | if (a2 <= 2) { 1187 | a2 = a2 + 1; 1188 | myNex.writeStr("a2.txt", String(a2)); 1189 | } 1190 | } 1191 | 1192 | break; 1193 | case 14: //K3 Set 1194 | if (SE == 0) { //If speed selected 1195 | if (s3 <= 95) { 1196 | s3 = s3 + 5; 1197 | myNex.writeStr("k3t.txt", String(s3)); 1198 | } 1199 | } else { 1200 | if (a3 <= 2) { 1201 | a3 = a3 + 1; 1202 | myNex.writeStr("a3.txt", String(a3)); 1203 | } 1204 | } 1205 | 1206 | break; 1207 | case 15: //K4 Set 1208 | if (SE == 0) { //If speed selected 1209 | if (s4 <= 95) { 1210 | s4 = s4 + 5; 1211 | myNex.writeStr("k4t.txt", String(s4)); 1212 | } 1213 | } else { 1214 | if (a4 <= 2) { 1215 | a4 = a4 + 1; 1216 | myNex.writeStr("a4.txt", String(a4)); 1217 | } 1218 | } 1219 | 1220 | break; 1221 | case 16: //K5 Set 1222 | if (SE == 0) { //If speed selected 1223 | if (s5 <= 95) { 1224 | s5 = s5 + 5; 1225 | myNex.writeStr("k5t.txt", String(s5)); 1226 | break; 1227 | } 1228 | } else { 1229 | if (a5 <= 2) { 1230 | a5 = a5 + 1; 1231 | myNex.writeStr("a5.txt", String(a5)); 1232 | break; 1233 | } 1234 | } 1235 | 1236 | case 17: //K6 Set 1237 | if (SE == 0) { //If speed selected 1238 | if (s6 <= 95) { 1239 | s6 = s6 + 5; 1240 | myNex.writeStr("k6t.txt", String(s6)); 1241 | } 1242 | } else { 1243 | if (a6 <= 2) { 1244 | a6 = a6 + 1; 1245 | myNex.writeStr("a6.txt", String(a6)); 1246 | } 1247 | } 1248 | 1249 | break; 1250 | 1251 | 1252 | } 1253 | 1254 | SendNextionValues(); 1255 | } 1256 | void trigger21() { // Sequencer Down arrow 1257 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1258 | Nextion_Wake(); 1259 | switch (Nextion_Func) { 1260 | 1261 | case 4: 1262 | if (Bounce <= 10 && Bounce != 500 && Bounce != 0) { 1263 | Bounce = Bounce - 1; // increase by 1 1264 | myNex.writeStr("t4.txt", String(Bounce)); // display value in t4 Bounce box on Nextion 1265 | myNex.writeStr("Bounce.txt", String(Bounce)); 1266 | } else { 1267 | Bounce = 10; //If greater than ten assume infinity 500 bring it down again to 10 1268 | myNex.writeStr("t4.txt", String(Bounce)); 1269 | myNex.writeStr("Bounce.txt", String(Bounce)); 1270 | } 1271 | break; 1272 | 1273 | case 12: //K1 Set 1274 | if (SE == 0) { //If speed selected 1275 | if (s1 >= 5) { 1276 | s1 = s1 - 5; 1277 | myNex.writeStr("k1t.txt", String(s1)); 1278 | } 1279 | } else { 1280 | if (a1 > 0) { 1281 | a1 = a1 - 1; 1282 | myNex.writeStr("a1.txt", String(a1)); 1283 | } 1284 | } 1285 | 1286 | break; 1287 | case 13: //K2 Set 1288 | if (SE == 0) { //If speed selected 1289 | if (s2 >= 5) { 1290 | s2 = s2 - 5; 1291 | myNex.writeStr("k2t.txt", String(s2)); 1292 | } 1293 | } else { 1294 | if (a2 > 0) { 1295 | a2 = a2 - 1; 1296 | myNex.writeStr("a2.txt", String(a2)); 1297 | } 1298 | } 1299 | 1300 | break; 1301 | case 14: //K3 Set 1302 | if (SE == 0) { //If speed selected 1303 | if (s3 >= 5) { 1304 | s3 = s3 - 5; 1305 | myNex.writeStr("k3t.txt", String(s3)); 1306 | } 1307 | } else { 1308 | if (a3 > 0) { 1309 | a3 = a3 - 1; 1310 | myNex.writeStr("a3.txt", String(a3)); 1311 | } 1312 | } 1313 | 1314 | break; 1315 | case 15: //K4 Set 1316 | if (SE == 0) { //If speed selected 1317 | if (s4 >= 5) { 1318 | s4 = s4 - 5; 1319 | myNex.writeStr("k4t.txt", String(s4)); 1320 | } 1321 | } else { 1322 | if (a4 > 0) { 1323 | a4 = a4 - 1; 1324 | myNex.writeStr("a4.txt", String(a4)); 1325 | } 1326 | } 1327 | 1328 | break; 1329 | case 16: //K5 Set 1330 | if (SE == 0) { //If speed selected 1331 | if (s5 >= 5) { 1332 | s5 = s5 - 5; 1333 | myNex.writeStr("k5t.txt", String(s5)); 1334 | } 1335 | } else { 1336 | if (a5 > 0) { 1337 | a5 = a5 - 1; 1338 | myNex.writeStr("a5.txt", String(a5)); 1339 | } 1340 | } 1341 | 1342 | break; 1343 | case 17: //K6 Set 1344 | if (SE == 0) { //If speed selected 1345 | if (s6 >= 5) { 1346 | s6 = s6 - 5; 1347 | myNex.writeStr("k6t.txt", String(s6)); 1348 | } 1349 | } else { 1350 | if (a6 > 0) { 1351 | a6 = a6 - 1; 1352 | myNex.writeStr("a6.txt", String(a6)); 1353 | } 1354 | } 1355 | 1356 | break; 1357 | } 1358 | SendNextionValues(); 1359 | } 1360 | 1361 | void trigger22() { //Sequencwer Ease setup arrow keys flip between speed and Easy value for each frame 1362 | if (SE == 0) { // 0=speed 1363 | SE = 1; 1364 | } else { //1=Acceloration or ease 1365 | SE = 0; 1366 | } 1367 | } 1368 | 1369 | void trigger23() { // Sequencer add key 1370 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1371 | Nextion_Wake(); 1372 | delay(20); 1373 | String k4String = myNex.readStr("k4t.txt"); 1374 | s4 = k4String.toInt(); 1375 | String k5String = myNex.readStr("k5t.txt"); 1376 | s5 = k5String.toInt(); 1377 | String k6String = myNex.readStr("k6t.txt"); 1378 | s6 = k6String.toInt(); 1379 | SendNextionValues(); 1380 | } 1381 | 1382 | //***********************PTZ CAMERA SETUPS*******************************************************************// 1383 | void trigger24() { //PTZ cam1 1384 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1385 | Nextion_Wake(); 1386 | PTZ_Cam = 1; 1387 | 1388 | if ( Cam1_RecordBut == 1) { 1389 | digitalWrite(LED, HIGH); 1390 | } else { 1391 | digitalWrite(LED, LOW); 1392 | } 1393 | SendNextionValues(); 1394 | } 1395 | 1396 | void trigger25() { //PTZ cam2 1397 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1398 | Nextion_Wake(); 1399 | PTZ_Cam = 2; 1400 | 1401 | if ( Cam2_RecordBut == 1) { 1402 | digitalWrite(LED, HIGH); 1403 | } else { 1404 | digitalWrite(LED, LOW); 1405 | } 1406 | SendNextionValues(); 1407 | } 1408 | void trigger26() { //PTZ cam3 1409 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1410 | Nextion_Wake(); 1411 | PTZ_Cam = 3; 1412 | 1413 | if ( Cam3_RecordBut == 1) { 1414 | digitalWrite(LED, HIGH); 1415 | } else { 1416 | digitalWrite(LED, LOW); 1417 | } 1418 | SendNextionValues(); 1419 | } 1420 | 1421 | 1422 | //void trigger75() { //PTZ cam4 Hex 4B 1423 | // myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1424 | // Nextion_Wake(); 1425 | // PTZ_Cam = 4; 1426 | // 1427 | // if ( Cam4_RecordBut == 1) { 1428 | // digitalWrite(LED, HIGH); 1429 | // } else { 1430 | // digitalWrite(LED, LOW); 1431 | // } 1432 | // SendNextionValues(); 1433 | //} 1434 | 1435 | void trigger27() { //PTZ Pos1 Set 1436 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1437 | Nextion_Wake(); 1438 | PTZ_Pose = 1; 1439 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1440 | SendNextionValues(); 1441 | delay(20); 1442 | PTZ_Pose = 0; 1443 | } 1444 | 1445 | void trigger28() { //PTZ Pos2 Set 1446 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1447 | Nextion_Wake(); 1448 | PTZ_Pose = 2; 1449 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1450 | SendNextionValues(); 1451 | delay(20); 1452 | PTZ_Pose = 0; 1453 | } 1454 | 1455 | void trigger29() { //PTZ Pos3 Set 1456 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1457 | Nextion_Wake(); 1458 | PTZ_Pose = 3; 1459 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1460 | SendNextionValues(); 1461 | delay(20); 1462 | PTZ_Pose = 0; 1463 | } 1464 | 1465 | void trigger30() { //PTZ Pos4 Set 1466 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1467 | Nextion_Wake(); 1468 | PTZ_Pose = 4; 1469 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1470 | SendNextionValues(); 1471 | delay(20); 1472 | PTZ_Pose = 0; 1473 | } 1474 | 1475 | void trigger31() { //PTZ Pos5 Set 1476 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1477 | Nextion_Wake(); 1478 | PTZ_Pose = 5; 1479 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1480 | SendNextionValues(); 1481 | delay(20); 1482 | PTZ_Pose = 0; 1483 | } 1484 | 1485 | void trigger32() { //PTZ Pos6 Set 1486 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1487 | Nextion_Wake(); 1488 | PTZ_Pose = 6; 1489 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1490 | SendNextionValues(); 1491 | delay(20); 1492 | PTZ_Pose = 0; 1493 | } 1494 | 1495 | void trigger76() { //PTZ Pos7 Set Hex4C 1496 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1497 | Nextion_Wake(); 1498 | PTZ_Pose = 7; 1499 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1500 | SendNextionValues(); 1501 | delay(20); 1502 | PTZ_Pose = 0; 1503 | } 1504 | 1505 | void trigger77() { //PTZ Pos8 Set Hex4D 1506 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1507 | Nextion_Wake(); 1508 | PTZ_Pose = 8; 1509 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1510 | SendNextionValues(); 1511 | delay(20); 1512 | PTZ_Pose = 0; 1513 | } 1514 | 1515 | void trigger78() { //PTZ Pos9 Set Hex4E 1516 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1517 | Nextion_Wake(); 1518 | PTZ_Pose = 9; 1519 | Serial.printf("\nPTZ_Pose set to %d \n", PTZ_Pose); 1520 | SendNextionValues(); 1521 | delay(20); 1522 | PTZ_Pose = 0; 1523 | } 1524 | //*******************************************************SET HARDWARE CAMERA ID*************************// 1525 | void trigger33() { //PTZ cam1 ID set 1526 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1527 | Nextion_Wake(); 1528 | PTZ_ID = 1; 1529 | SendNextionValues(); 1530 | delay(20); 1531 | PTZ_ID = 0; 1532 | } 1533 | 1534 | void trigger34() { //PTZ cam2 ID set 1535 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1536 | Nextion_Wake(); 1537 | PTZ_ID = 2; 1538 | SendNextionValues(); 1539 | PTZ_ID = 0; 1540 | } 1541 | 1542 | void trigger35() { //PTZ cam3 ID set 1543 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1544 | Nextion_Wake(); 1545 | PTZ_ID = 3; 1546 | SendNextionValues(); 1547 | PTZ_ID = 0; 1548 | } 1549 | void trigger79() { //PTZ cam4 ID set hex 4F 1550 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1551 | Nextion_Wake(); 1552 | PTZ_ID = 4; 1553 | SendNextionValues(); 1554 | PTZ_ID = 0; 1555 | } 1556 | 1557 | void trigger36() { //PTZ Active true 1558 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1559 | Nextion_Wake(); 1560 | PTZ_Active = 1; 1561 | PTZ_Cam = 1; 1562 | SendNextionValues(); 1563 | } 1564 | 1565 | void trigger37() { //Home button 1566 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1567 | Nextion_Wake(); 1568 | PTZ_Active = 0; 1569 | PTZ_Cam = 0; 1570 | digitalWrite(LED, LOW); 1571 | lastRecordBut = 0; 1572 | RecordBut = 0; 1573 | SendNextionValues(); 1574 | } 1575 | 1576 | void trigger38() { //PTZ Save Pose 1577 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1578 | Nextion_Wake(); 1579 | PTZ_SaveP = 1; 1580 | SendNextionValues(); 1581 | PTZ_SaveP = 0; 1582 | } 1583 | 1584 | void trigger39() { //Stop motion Play command 1585 | Nextion_Wake(); 1586 | digitalWrite(LED, HIGH); 1587 | SM = 1; 1588 | SendNextionValues(); 1589 | delay(50); 1590 | SM = 0; 1591 | } 1592 | 1593 | void trigger40() { //Stop motion cancel command 1594 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1595 | Nextion_Wake(); 1596 | SC = 1; 1597 | SendNextionValues(); 1598 | 1599 | } 1600 | void trigger41() { //Nextion Stop Motion SeqTime 1601 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1602 | Nextion_Func = 20; 1603 | 1604 | } 1605 | 1606 | void trigger42() { // Stop Motion Shutter open time 1607 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1608 | Nextion_Wake(); 1609 | Nextion_Func = 21; 1610 | } 1611 | 1612 | void trigger43() { // Stop Motion FPS 2B 1613 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1614 | Nextion_Wake(); 1615 | Nextion_Func = 22; 1616 | 1617 | } 1618 | 1619 | void trigger44() { // Clear all keys back to 0 2C 1620 | //Clear all keyframes back to 0 1621 | clrK = 1; 1622 | SendNextionValues(); 1623 | clrK = 0; 1624 | } 1625 | 1626 | void trigger45() { //Set inital values for Stopmotion 1627 | 1628 | // TpsD = 1000; 1629 | SendNextionValues(); 1630 | stopMactive = 1; 1631 | } 1632 | 1633 | void trigger46() { //clockwise focus/Zoom limit set- hex 2E 1634 | switch (PTZ_Cam) { 1635 | case 1: 1636 | LM = 1; 1637 | SendNextionValues(); 1638 | Serial.println("\nLM set to 1:\n"); 1639 | break; 1640 | case 2: 1641 | LM = 3; 1642 | SendNextionValues(); 1643 | Serial.println("\nLM set to 3:\n"); 1644 | break; 1645 | case 3: 1646 | LM = 5; 1647 | SendNextionValues(); 1648 | Serial.println("\nLM set to 5:\n"); 1649 | break; 1650 | } 1651 | } 1652 | void trigger47() { //counter clockwise focus/Zoom limit set - hex 2F 1653 | switch (PTZ_Cam) { 1654 | case 1: 1655 | LM = 2; 1656 | SendNextionValues(); 1657 | Serial.println("\nLM set to 2:\n"); 1658 | break; 1659 | case 2: 1660 | LM = 4; 1661 | SendNextionValues(); 1662 | Serial.println("\nLM set to 4:\n"); 1663 | break; 1664 | case 3: 1665 | LM = 6; 1666 | SendNextionValues(); 1667 | Serial.println("\nLM set to 6:\n"); 1668 | break; 1669 | } 1670 | } 1671 | void trigger48() { //Finished - hex 30 1672 | LM = 0; 1673 | SendNextionValues(); 1674 | Serial.println("\nLM set to: 0\n"); 1675 | } 1676 | 1677 | void trigger49() { //Camera 0 set ID hex 31 1678 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1679 | Nextion_Wake(); 1680 | PTZ_ID = 5; 1681 | SendNextionValues(); 1682 | PTZ_ID = 0; 1683 | } 1684 | //void trigger50() { //Dolly path Sraight line Hex 32 1685 | // Serial.println("\nTrigger50 active\n"); 1686 | // DollyPath = 0; //This can be 0 or 1 0 being straight 1 being curved 1687 | //} 1688 | // 1689 | //void trigger51() { //Dolly path Curved Hex33 1690 | // Serial.println("\nTrigger51 active\n"); 1691 | // DollyPath = 1; //This can be 0 or 1 1692 | //} 1693 | // 1694 | //void trigger52() { //Dolly path 360deg New trigger Hex34 1695 | // Serial.println("\nTrigger52 active\n"); 1696 | // Dolly360 = 1; //This can be 0 or 1 1 being true for 360 moves 1697 | //} 1698 | // 1699 | //void trigger53() { //New trigger Hex35 1700 | // Serial.println("\nTrigger53 active\n"); 1701 | // ThreeDscanSetup = 0; 1702 | //} 1703 | 1704 | //void trigger54() { //New trigger Hex36 1705 | // Serial.println("\nTrigger54 active\n"); 1706 | // ThreeDscanSetup = 1; 1707 | //} 1708 | // 1709 | //void trigger55() { //New trigger Hex37 1710 | // Serial.println("\nTrigger55 active\n"); 1711 | // ThreeDscanSetup = 3; 1712 | //} 1713 | 1714 | void trigger56() { //Number of Vertical slider moves Hex38 1715 | Serial.println("\nTrigger56 active\n"); 1716 | Nextion_Func = 23; 1717 | } 1718 | 1719 | void trigger57() { //Number of scan shots per revolution Hex39 1720 | Serial.println("\nTrigger57 active\n"); 1721 | Nextion_Func = 24; 1722 | } 1723 | 1724 | void trigger58() { //New trigger Hex3A 1725 | Serial.println("\nTrigger58 active\n"); 1726 | } 1727 | 1728 | void trigger59() { //New trigger Hex3B 1729 | Serial.println("\nTrigger59 active\n"); 1730 | } 1731 | 1732 | void trigger60() { //IP1 trigger Hex3C 1733 | Serial.println("\nIP1 set\n"); 1734 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1735 | Nextion_Wake(); 1736 | Nextion_Func = 25; 1737 | } 1738 | void trigger61() { //IP2 trigger Hex3D 1739 | Serial.println("\nIP2 set\n"); 1740 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1741 | Nextion_Wake(); 1742 | Nextion_Func = 26; 1743 | } 1744 | void trigger62() { //IP3 trigger Hex3E 1745 | Serial.println("\nIP3 set\n"); 1746 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1747 | Nextion_Wake(); 1748 | Nextion_Func = 27; 1749 | } 1750 | void trigger63() { //IP4 trigger Hex3F 1751 | Serial.println("\nIP4 set \n"); 1752 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1753 | Nextion_Wake(); 1754 | Nextion_Func = 28; 1755 | } 1756 | void trigger64() { //UDP trigger Hex40 1757 | Serial.println("\nUDP set\n"); 1758 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1759 | Nextion_Wake(); 1760 | Nextion_Func = 29; 1761 | } 1762 | void trigger65() { //Set IP address trigger Hex41 1763 | Serial.println("\nSet New IP Values\n"); 1764 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1765 | Nextion_Wake(); 1766 | IPR = 3; 1767 | SendNextionValues(); 1768 | //IP1 = 0; IP2 = 0; IP3 = 0; IP4 = 0; UDP = 0; IPR = 0; //Re-set address values to 0 1769 | } 1770 | void trigger66() { //Send requesting for current IPvalues IP address trigger Hex42 1771 | Serial.println("\nGet current device IP Values\n"); 1772 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1773 | Nextion_Wake(); 1774 | IPR = 1; 1775 | SendNextionValues(); 1776 | 1777 | IPR = 2; 1778 | 1779 | } 1780 | void trigger67() { //IP UP arror address trigger Hex43 1781 | Serial.println("\nGet current device IP Values\n"); 1782 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1783 | Nextion_Wake(); 1784 | switch (Nextion_Func) { 1785 | 1786 | case 25: 1787 | IP1 = IP1 + 1; // Reduce by 1 for down arrow 1788 | myNex.writeStr("IP1.txt", String(IP1)); 1789 | delay(20); 1790 | break; 1791 | case 26: 1792 | //IP adress 1 1793 | IP2 = IP2 + 1; // Reduce by 1 for down arrow 1794 | myNex.writeStr("IP2.txt", String(IP2)); 1795 | delay(20); 1796 | break; 1797 | case 27: 1798 | IP3 = IP3 + 1; // Reduce by 1 for down arrow 1799 | myNex.writeStr("IP3.txt", String(IP3)); 1800 | delay(20); 1801 | break; 1802 | case 28: 1803 | //IP adress 1 1804 | IP4 = IP4 + 1; // Reduce by 1 for down arrow 1805 | myNex.writeStr("IP4.txt", String(IP4)); 1806 | delay(20); 1807 | break; 1808 | case 29: 1809 | if (UDP == 1259) { //IP adress 1 1810 | UDP = 5678; // Reduce by 1 for down arrow 1811 | myNex.writeStr("UDP.txt", String(UDP)); 1812 | } 1813 | delay(20); 1814 | break; 1815 | case 30: 1816 | //IP adress 1 1817 | IPGW = IPGW + 1; // Reduce by 1 for down arrow 1818 | myNex.writeStr("IPGW.txt", String(IPGW)); 1819 | delay(20); 1820 | break; 1821 | case 31: //Delay bounce/Return time 1822 | //Delay down 1823 | if (BD < 10) { 1824 | BD = BD + 1; // Up arrow +1 1825 | myNex.writeStr("delaytime.txt", String(BD)); 1826 | delay(20); 1827 | SysMemory.begin("BD", false); 1828 | SysMemory.putUInt("BD", BD); 1829 | SysMemory.end(); 1830 | SendNextionValues(); 1831 | } 1832 | break; 1833 | } 1834 | } 1835 | void trigger68() { //IP down arror address trigger Hex44 1836 | Serial.println("\nGet current device IP Values\n"); 1837 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1838 | Nextion_Wake(); 1839 | switch (Nextion_Func) { 1840 | 1841 | case 25: 1842 | IP1 = IP1 - 1; // Reduce by 1 for down arrow 1843 | myNex.writeStr("IP1.txt", String(IP1)); 1844 | delay(20); 1845 | break; 1846 | case 26: 1847 | //IP adress 1 1848 | IP2 = IP2 - 1; // Reduce by 1 for down arrow 1849 | myNex.writeStr("IP2.txt", String(IP2)); 1850 | delay(20); 1851 | break; 1852 | case 27: 1853 | IP3 = IP3 - 1; // Reduce by 1 for down arrow 1854 | myNex.writeStr("IP3.txt", String(IP3)); 1855 | delay(20); 1856 | break; 1857 | case 28: 1858 | //IP adress 1 1859 | IP4 = IP4 - 1; // Reduce by 1 for down arrow 1860 | myNex.writeStr("IP4.txt", String(IP4)); 1861 | delay(20); 1862 | break; 1863 | case 29: 1864 | if (UDP == 5678) { //IP adress 1 1865 | UDP = 1259; // Reduce by 1 for down arrow 1866 | myNex.writeStr("UDP.txt", String(UDP)); 1867 | } 1868 | delay(20); 1869 | break; 1870 | case 30: 1871 | //IP adress 1 1872 | IPGW = IPGW - 1; // Reduce by 1 for down arrow 1873 | myNex.writeStr("IPGW.txt", String(IPGW)); 1874 | delay(20); 1875 | break; 1876 | case 31: 1877 | //Delay down 1878 | if (BD > 1) { 1879 | BD = BD - 1; // Reduce by 1 for down arrow 1880 | myNex.writeStr("delaytime.txt", String(BD)); 1881 | delay(20); 1882 | SysMemory.begin("BD", false); 1883 | SysMemory.putUInt("BD", BD); 1884 | SysMemory.end(); 1885 | SendNextionValues(); 1886 | } 1887 | break; 1888 | } 1889 | } 1890 | void trigger69() { //IPGW trigger Hex45 1891 | Serial.println("\nIPGW set\n"); 1892 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1893 | Nextion_Wake(); 1894 | Nextion_Func = 30; 1895 | } 1896 | 1897 | void trigger70() { //Pan Joy speed Hex46 1898 | 1899 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1900 | Nextion_Wake(); 1901 | Nextion_Func = 23; 1902 | } 1903 | void trigger71() { //Tilt Joy speed Hex47 1904 | 1905 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1906 | Nextion_Wake(); 1907 | Nextion_Func = 24; 1908 | } 1909 | void trigger72() { //Tally On Hex48 1910 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1911 | Nextion_Wake(); 1912 | if (TLY == 0) { 1913 | TLY = 1; 1914 | SendNextionValues(); 1915 | } 1916 | } 1917 | 1918 | void trigger73() { //Tally Off Hex49 1919 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1920 | Nextion_Wake(); 1921 | if (TLY == 1) { 1922 | TLY = 0; 1923 | SendNextionValues(); 1924 | } 1925 | } 1926 | void trigger74() { //Slider length Hex4A 1927 | 1928 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1929 | Nextion_Wake(); 1930 | String SLDLstring = myNex.readStr("SLDL.txt"); 1931 | if (SLDLstring.toInt() != 0) { 1932 | SLDL = SLDLstring.toInt(); 1933 | SendNextionValues(); 1934 | } 1935 | } 1936 | void trigger84() { //Delay Bounce Return Hex54 1937 | Serial.println("\nDelay set\n"); 1938 | myNex.writeStr("t10.txt", "Bat:" + String(NexBatV) + "v"); 1939 | Nextion_Wake(); 1940 | delay(20); 1941 | myNex.writeStr("delaytime.txt", String(BD)); 1942 | Nextion_Func = 31; 1943 | } 1944 | void formatMacAddress(const uint8_t *macAddr, char *buffer, int maxLength) 1945 | { 1946 | snprintf(buffer, maxLength, "%02x:%02x:%02x:%02x:%02x:%02x", macAddr[0], macAddr[1], macAddr[2], macAddr[3], macAddr[4], macAddr[5]); 1947 | } 1948 | 1949 | 1950 | 1951 | //*************************************ESP_NOW READ INCOMMING VALUES*************************// 1952 | void receiveCallback(const uint8_t *macAddr, const uint8_t *incomingData, int Len) { 1953 | // only allow a maximum of 250 characters in the message + a null terminating byte 1954 | char buffer[ESP_NOW_MAX_DATA_LEN + 1]; 1955 | // int msgLen = min(ESP_NOW_MAX_DATA_LEN, dataLen); 1956 | 1957 | memcpy(&incomingValues, incomingData, sizeof(incomingValues)); 1958 | //memcpy(&incomingValues, Data, sizeof(incomingValues)); 1959 | //Read all current Nextion values 1960 | 1961 | Snd = int(incomingValues.Snd); //Senders Ident 1=Controller 2=Slider 3=PanTilt 4=TurnT 5=Jib 1962 | 1963 | switch (Snd) { //Only Change the Device state if the message was sent by the device 1964 | case 2: 1965 | Sld = int(incomingValues.Sld); //Slider available 1 or 0 1966 | break; 1967 | case 3: 1968 | PT = int(incomingValues.PT); //Pan Tilt available 1 or 0 1969 | break; 1970 | case 4: 1971 | TT = int(incomingValues.TT); //Turntable available 1 or 0 1972 | break; 1973 | case 5: 1974 | JB = int(incomingValues.JB); //Jib available 1 or 0 1975 | break; 1976 | } 1977 | 1978 | 1979 | //Ease_Value = int(incomingValues.Ez); // Acceloration control 1980 | Bounce = int(incomingValues.Bo); // Number of bounces 1981 | Crono_time = int(incomingValues.Cro); //Time in sec of system move 1982 | //Nextion_Func = int(incomingValues.Fnc); //Current Func of nextion display 1983 | Tps = int(incomingValues.Tps); //Timlapse frames 1984 | //TpsD = int(incomingValues.TpsD); //Timplapse delay or shutter open time in Bulb mode 1985 | TpsM = int(incomingValues.TpsM); //Timelapse move comand used to trigger next move from nextion 1986 | in_position = long(incomingValues.In); //InPoint 1987 | out_position = long(incomingValues.Out); //OutPoint 1988 | Nextion_play = int(incomingValues.Play); //playbutton pressed on nextion 1989 | But_Com = int(incomingValues.But); //playbutton pressed on Slave 1990 | InP = int(incomingValues.InP); //InPoint button state 0-2 1991 | OutP = int(incomingValues.OutP); //OutPoint button state 0-2 1992 | SMC = int(incomingValues.SMC); //StopMotion counter 1993 | PTZ_Cam = int(incomingValues.CA); 1994 | 1995 | myNex.writeStr("bounce.txt", String(Bounce)); //Bounce counter 1996 | myNex.writeStr("out.txt", String(out_position)); 1997 | myNex.writeStr("in.txt", String(in_position)); 1998 | myNex.writeStr("tlps.txt", String(Tps)); 1999 | myNex.writeStr("ease .txt", String(Ease_Value)); 2000 | //myNex.writeStr("mess.txt", String(mess)); 2001 | 2002 | 2003 | // strncpy(buffer, (const char *)data, msgLen); 2004 | // make sure we are null terminated 2005 | // buffer[msgLen] = 0; 2006 | // format the mac address 2007 | char macStr[18]; 2008 | formatMacAddress(macAddr, macStr, 18); 2009 | // debug log the message to the serial port 2010 | // Serial.printf("Received message from: %s - %s\n", macStr, buffer); 2011 | // Serial.print("Last Packet Size: "); 2012 | // Serial.println (sizeof(incomingValues)); 2013 | // Put here what you want to do with the received data 2014 | // if (strcmp("on", buffer) == 0) 2015 | // { 2016 | // ledOn = true; 2017 | // } 2018 | // else 2019 | // { 2020 | // ledOn = false; 2021 | // } 2022 | // digitalWrite(2, ledOn); 2023 | } 2024 | 2025 | // callback when data is sent 2026 | void sentCallback(const uint8_t *macAddr, esp_now_send_status_t status) 2027 | { 2028 | char macStr[18]; 2029 | formatMacAddress(macAddr, macStr, 18); 2030 | // Serial.print("Last Packet Sent to: "); 2031 | // Serial.println(macStr); 2032 | // Serial.print("Last Packet Send Status: "); 2033 | // Serial.println(status == ESP_NOW_SEND_SUCCESS ? "Delivery Success" : "Delivery Fail"); 2034 | } 2035 | 2036 | 2037 | //Setup ESP_NOW connection 2038 | void broadcast(const String & message) 2039 | { 2040 | // this will broadcast a message to everyone in range 2041 | uint8_t broadcastAddress[] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; 2042 | esp_now_peer_info_t peerInfo = {}; 2043 | memcpy(&peerInfo.peer_addr, broadcastAddress, 6); 2044 | if (!esp_now_is_peer_exist(broadcastAddress)) 2045 | { 2046 | esp_now_add_peer(&peerInfo); 2047 | } 2048 | esp_err_t result = esp_now_send(broadcastAddress, (const uint8_t *)message.c_str(), message.length()); 2049 | 2050 | // and this will send a message to a specific device 2051 | /*uint8_t peerAddress[] = {0x3C, 0x71, 0xBF, 0x47, 0xA5, 0xC0}; 2052 | esp_now_peer_info_t peerInfo = {}; 2053 | memcpy(&peerInfo.peer_addr, peerAddress, 6); 2054 | if (!esp_now_is_peer_exist(peerAddress)) 2055 | { 2056 | esp_now_add_peer(&peerInfo); 2057 | } 2058 | esp_err_t result = esp_now_send(peerAddress, (const uint8_t *)message.c_str(), message.length());*/ 2059 | if (result == ESP_OK) 2060 | { 2061 | Serial.println("Broadcast message success"); 2062 | } 2063 | else if (result == ESP_ERR_ESPNOW_NOT_INIT) 2064 | { 2065 | Serial.println("ESPNOW not Init."); 2066 | } 2067 | else if (result == ESP_ERR_ESPNOW_ARG) 2068 | { 2069 | Serial.println("Invalid Argument"); 2070 | } 2071 | else if (result == ESP_ERR_ESPNOW_INTERNAL) 2072 | { 2073 | Serial.println("Internal Error"); 2074 | } 2075 | else if (result == ESP_ERR_ESPNOW_NO_MEM) 2076 | { 2077 | Serial.println("ESP_ERR_ESPNOW_NO_MEM"); 2078 | } 2079 | else if (result == ESP_ERR_ESPNOW_NOT_FOUND) 2080 | { 2081 | Serial.println("Peer not found."); 2082 | } 2083 | else 2084 | { 2085 | Serial.println("Unknown error"); 2086 | } 2087 | } 2088 | //*******************************ESP_NOW Send VALUES****************************// 2089 | void SendNextionValues() { 2090 | broadcast (""); 2091 | NextionValues.Snd = 1; //Tells the controller who sent the message 1=Controller 2=Slider 3=PanTilt 4=Turntable 5=Jib 2092 | NextionValues.Ez = Ease_Value; // Acceloration control 2093 | NextionValues.Bo = Bounce; // Number of bounces 2094 | NextionValues.Cro = Crono_time; // Time in sec of system move 2095 | //NextionValues.Fnc = Nextion_Func; // Current Func of nextion display 2096 | NextionValues.Tps = Tps; // Timlapse frames 2097 | NextionValues.TpsD = TpsD; // Timplapse delay or shutter open time in Bulb mode 2098 | NextionValues.TpsM = TpsM; // Timelapse move command 2099 | NextionValues.In = in_position; // InPoint step position value 2100 | NextionValues.Out = out_position; // OutPoint Step position value 2101 | NextionValues.Play = Nextion_play; // play comand 2102 | NextionValues.But = But_Com; // playbutton pressed on Slave 2103 | NextionValues.InP = InP; // InPoint button state 0-2 2104 | NextionValues.OutP = OutP; // OutPoint button state 0-2 2105 | NextionValues.Sld = Sld; // Slider present 0-1 2106 | NextionValues.PT = PT; // Pan Tilt present 0-1 2107 | NextionValues.TT = TT; // Turntable present 0-1 2108 | NextionValues.JB = JB; // Jib present 0-1 2109 | NextionValues.s1 = s1; // Sequencer key speed 2110 | NextionValues.s2 = s2; // Sequencer key speed 2111 | NextionValues.s3 = s3; // Sequencer key speed 2112 | NextionValues.s4 = s4; // Sequencer key speed 2113 | NextionValues.s5 = s5; // Sequencer key speed 2114 | NextionValues.s6 = s6; // Sequencer key speed 2115 | NextionValues.P1 = P1; // k1 set button 0-2 2116 | NextionValues.P2 = P2; // k2 set button 0-2 2117 | NextionValues.P3 = P3; // k3 set button 0-2 2118 | NextionValues.P4 = P4; // k4 set button 0-2 2119 | NextionValues.P5 = P5; // k5 set button 0-2 2120 | NextionValues.P6 = P6; // k6 set button 0-2 2121 | // NextionValues.a1 = 3; // Acceloration values 2122 | // NextionValues.a2 = 3; 2123 | // NextionValues.a3 = 3; 2124 | // NextionValues.a4 = 3; 2125 | // NextionValues.a5 = 3; 2126 | // NextionValues.a6 = 3 ; 2127 | //PTZ variables 2128 | NextionValues.Ma = masterA; //Master acceloration pot 2129 | 2130 | NextionValues.Ts = Tilt_J_Speed; //Joystick Speed 2131 | NextionValues.Ps = Pan_J_Speed; 2132 | NextionValues.Fs = Foc_J_Speed; 2133 | NextionValues.Zs = Zoom_J_Speed; 2134 | NextionValues.Ss = Slid_J_Speed; 2135 | 2136 | 2137 | NextionValues.ID = PTZ_ID ; 2138 | NextionValues.CA = PTZ_Cam; 2139 | NextionValues.SP = PTZ_SaveP; 2140 | NextionValues.Pz = PTZ_Pose; 2141 | 2142 | NextionValues.SM = SM; 2143 | NextionValues.SC = SC; 2144 | NextionValues.Rc = RecordBut; //Play button state for PTZ 2145 | NextionValues.LM = LM; //Focus/Zoom Limits set 1-6 2146 | NextionValues.Jb = usejoy; 2147 | NextionValues.clrK = clrK; 2148 | 2149 | NextionValues.IPR = IPR; 2150 | NextionValues.IP1 = IP1; 2151 | NextionValues.IP2 = IP2; 2152 | NextionValues.IP3 = IP3; 2153 | NextionValues.IP4 = IP4; 2154 | NextionValues.IPGW = IPGW; 2155 | NextionValues.UDP = UDP; 2156 | NextionValues.TLY = TLY; //Tally light active 1 inative 0 2157 | NextionValues.BD = BD; //Bounce / return delay in seconds 2158 | //Serial.print("\na1="); 2159 | //Serial.print(NextionValues.a1); 2160 | 2161 | uint8_t broadcastAddress[] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; 2162 | esp_now_send(broadcastAddress, (uint8_t *) &NextionValues, sizeof(NextionValues)); 2163 | } 2164 | 2165 | void UpdateSEQ() { 2166 | Nextion_Wake(); 2167 | delay(800); 2168 | myNex.writeStr("k1t.txt", String(s1)); 2169 | myNex.writeStr("k2t.txt", String(s2)); 2170 | myNex.writeStr("k3t.txt", String(s3)); 2171 | myNex.writeStr("k4t.txt", String(s4)); 2172 | myNex.writeStr("k5t.txt", String(s5)); 2173 | myNex.writeStr("k6t.txt", String(s6)); 2174 | } 2175 | 2176 | //*************************************** Joystick contro s******************************************** 2177 | void ReadAnalog() { //Read joystick positions 2178 | tiltS = analogRead(tiltS_PIN); 2179 | panS = analogRead(panS_PIN); 2180 | focusS = analogRead(focusS_PIN); 2181 | zoomS = analogRead(zoomS_PIN); 2182 | slidS = analogRead(slidS_PIN); 2183 | 2184 | masterA = analogRead(masterA_PIN); 2185 | masterA = constrain(masterA, 900, 4000); 2186 | 2187 | 2188 | 2189 | 2190 | tiltS = (tiltS - tilt_AVG); 2191 | panS = (panS - pan_AVG); 2192 | focusS = (focusS - foc_AVG); 2193 | zoomS = (zoomS - zoom_AVG); 2194 | slidS = (slidS - slid_AVG); 2195 | 2196 | //Serial.println(masterA); //GPIO33 2197 | 2198 | //**Tilt Control** 2199 | if ( tiltS > 300) { //Tilt moving forwards send update 2200 | Tilt_J_Speed = (tiltS); 2201 | sendjoy = true; 2202 | } 2203 | if (tiltS < -300) { //Tilt moving Backwards send update 2204 | Tilt_J_Speed = (tiltS); 2205 | sendjoy = true; 2206 | } 2207 | //**Pan Control** 2208 | if ( panS > 200) { //Pan moving forwards send update 2209 | Pan_J_Speed = (panS / 4); 2210 | sendjoy = true; 2211 | } 2212 | if (panS < -300) { //Pan moving Backwards send update 2213 | Pan_J_Speed = (panS / 2) ; 2214 | sendjoy = true; 2215 | } 2216 | //**Focus Control** 2217 | if ( focusS > 400) { //Focus moving forwards send update 2218 | Foc_J_Speed = (focusS); 2219 | sendjoy = true; 2220 | } 2221 | if (focusS < -400) { //Focus moving Backwards send update 2222 | Foc_J_Speed = (focusS) ; 2223 | sendjoy = true; 2224 | } 2225 | 2226 | if (slidS > 300) { //Slider moving forwards send update 2227 | Slid_J_Speed = (slidS - 100); 2228 | sendjoy = true; 2229 | } 2230 | if (slidS < -300) { //Slider moving Backwards send update 2231 | Slid_J_Speed = (slidS - 200) ; 2232 | sendjoy = true; 2233 | } 2234 | //**Zoom Control** 2235 | // if (zoomS > 400) { //Zoom moving forwards send update 2236 | // Serial.println("ZoomStepper move forward"); 2237 | // 2238 | // Zoom_J_Speed = (zoomS); 2239 | // Serial.println(Zoom_J_Speed); 2240 | // sendjoy = true; 2241 | // } 2242 | // if (zoomS < -400) { //Zoom moving Backwards send update 2243 | // Serial.println("ZoomStepper move Backwards"); 2244 | // Zoom_J_Speed = (zoomS); 2245 | // Serial.println(Zoom_J_Speed); 2246 | // sendjoy = true; 2247 | // } 2248 | //**Slider Control** 2249 | 2250 | //*********Wright out all the above values here****************** 2251 | if (sendjoy) { 2252 | SendNextionValues(); //Send all values 2253 | sendjoy = false; 2254 | joypass = true; 2255 | } else { //send a final stopmove 2256 | if (joypass) { 2257 | Slid_J_Speed = 0; 2258 | Pan_J_Speed = 0; 2259 | Tilt_J_Speed = 0; 2260 | Foc_J_Speed = 0; 2261 | Zoom_J_Speed = 0; 2262 | SendNextionValues(); //Send all values 2263 | //Serial.println("slid_Accel"); 2264 | //Serial.println(slidA); 2265 | sendjoy = false; 2266 | joypass = false; 2267 | } 2268 | } 2269 | } 2270 | void InitialValues() { 2271 | 2272 | //Set the values to zero before averaging 2273 | int temp_tilt = 0; 2274 | int temp_pan = 0; 2275 | int temp_foc = 0; 2276 | int temp_zoom = 0; 2277 | int temp_slid = 0; 2278 | 2279 | for (int i = 0; i < 100; i++) { 2280 | temp_tilt += analogRead(tiltS_PIN); 2281 | delay(10); //allowing a little time between two readings 2282 | } 2283 | for (int i = 0; i < 100; i++) { 2284 | temp_pan += analogRead(panS_PIN); 2285 | delay(10); //allowing a little time between two readings 2286 | } 2287 | for (int i = 0; i < 100; i++) { 2288 | temp_slid += analogRead(slidS_PIN); 2289 | delay(10); //allowing a little time between two readings 2290 | } 2291 | for (int i = 0; i < 100; i++) { 2292 | temp_foc += analogRead(focusS_PIN); 2293 | delay(10); //allowing a little time between two readings 2294 | } 2295 | for (int i = 0; i < 100; i++) { 2296 | temp_zoom += analogRead(zoomS_PIN); 2297 | delay(10); //allowing a little time between two readings 2298 | } 2299 | 2300 | 2301 | tilt_AVG = temp_tilt / 100; 2302 | pan_AVG = temp_pan / 100; 2303 | slid_AVG = temp_slid / 100; 2304 | foc_AVG = temp_foc / 100; 2305 | zoom_AVG = temp_zoom / 100; 2306 | 2307 | 2308 | 2309 | // Serial.println("tilt_Average"); 2310 | // Serial.println(tilt_AVG); 2311 | // Serial.println("Pan_Average"); 2312 | // Serial.println(pan_AVG); 2313 | // Serial.println("slid_Average"); 2314 | // Serial.println(slid_AVG); 2315 | // Serial.println("slid_Accel"); 2316 | // Serial.println(slidA); 2317 | } 2318 | void Load_SysMemory() { 2319 | //SysMemory Recover last setup 2320 | SysMemory.begin("BD", false); //Recover the last Bounce delay 2321 | BD = SysMemory.getUInt("BD", 1); 2322 | SysMemory.end(); 2323 | } 2324 | -------------------------------------------------------------------------------- /Compact_WIFI_Controler/Readme: -------------------------------------------------------------------------------- 1 | Update 6.03 Fixes a bug where shutter speed in tim-lapse was not being respected 2 | Update 6.02: Fixed a bug where ease values were not updating correctly 3 | 4 | General: 5 | There are three possible 2.8" Nextion displays that can be used by the system BASIC, DISCOVERY, ENHANCED 6 | Thay can be identified from the colour of the PCB board on the display. 7 | Blue-Basic 8 | Orange-Discovery 9 | Black- Enhanced 10 | 11 | For our purposes thay all work the same But the firmware requires you install for the specific model 12 | Hense the reason there are three Nextion files here 13 | 14 | The ESP32 file here is for the ESP32 feather remember to set the correct board in the board manager. 15 | 16 | The Nextion file *.tft needs to be copied to a 32GB or lower SD card. Insert the card into your nextion and switch on 17 | the update is automatic. Note only one *.tft file can be on the SD card. The SD card must be formated to FAT32 18 | FAT32 can only format up to 32GB 19 | -------------------------------------------------------------------------------- /Copyright Licence: -------------------------------------------------------------------------------- 1 | Copyright 2023 Colin Henderson Digital Bird Motion Control 2 | 3 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 4 | 5 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 6 | 7 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 8 | 9 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 10 | 11 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 12 | -------------------------------------------------------------------------------- /DB3/DB3_VISCA_Decoder_v6.00.ino: -------------------------------------------------------------------------------- 1 | /* 2 | 3 | Digital Bird Visca Decoder- POE ethernet UDP to UART export v6.00 Oct 2023 4 | change Log: 5 | 6 | Version 6.00 7 | Requires you must be running V6 or above of the PTZplus WIFI controller firmware 8 | 9 | Update Notes v6.0: 17th Oct 2023 10 | 1) Removed any referance to nvs_flash.h which was no longer available with Arduino IDE 2 11 | 2) Updated all software to V6.00 In future all software on the system will have the same first version number to be compatable e.g V6 the second part of the number will be used for indevidual device updates 12 | in this way it should be much more clear the current compatable versioning across all devices on the system. 13 | 14 | 1) Preset speed added to viscacommand set allowing you to modify the speed of preset moves 15 | 2) Bug Fix where IP was not always being received correctly from the upper head CPU at startup 16 | 17 | 18 | Copyright 2023 Colin Henderson Digital Bird Motion Control 19 | 20 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 21 | 22 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 23 | 24 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 25 | 26 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 27 | 28 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY 29 | AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 30 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 31 | IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | 33 | Thx! 34 | 35 | *///////////////////////////////////////////////////////////////////////////////////////////////////////////// 36 | #define DEBUG_ETHERNET_WEBSERVER_PORT Serial 37 | // Debug Level from 0 to 4 38 | #define _ETHERNET_WEBSERVER_LOGLEVEL_ 3 39 | #include 40 | #include 41 | HardwareSerial UARTport(2); // use UART2 42 | #include 43 | #include 44 | #include 45 | #include 46 | 47 | 48 | 49 | // Select the IP address according to your local network 50 | IPAddress myIP(192, 168, 137, 80); 51 | IPAddress myGW(192, 168, 137, 1); 52 | IPAddress mySN(255, 255, 255, 0); 53 | IPAddress myDNS(192, 168, 137, 1); //Adress to send out on 54 | 55 | char timeServer[] = "time.nist.gov"; // NTP server 56 | unsigned int localPort = 1259; // local port to listen for UDP packets 57 | 58 | const int NTP_PACKET_SIZE = 48; // NTP timestamp is in the first 48 bytes of the message 59 | const int UDP_TIMEOUT = 10; // timeout in miliseconds to wait for an UDP packet to arrive 60 | 61 | byte packetBuffer[NTP_PACKET_SIZE]; // buffer to hold incoming and outgoing packets 62 | 63 | // A UDP instance to let us send and receive packets over UDP 64 | WiFiUDP Udp; 65 | 66 | // send an NTP request to the time server at the given address 67 | 68 | 69 | //Example return codes 70 | byte acknowledge[3] = {0x90, 0x41, 0xFF}; // Return for accept command 71 | byte acceptC[3] = {0x90, 0x38, 0xFF}; // Return for accept command 72 | 73 | //Required for inital camera setup 74 | byte PTposition[12] = {0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF}; //Pan Tilt current position reply 11 75 | byte ZoomPosition[7] = {0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0xFF}; //Zoom position reply = Zoom x1 76 | byte FocusPosition[7] = {0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0xFF}; //Focus position reply = infinity 77 | byte Confirm[3] = {0x90, 0x42, 0xFF}; //Accept comands return 78 | byte complete[3] = {0x90, 0x51, 0xFF}; // Return code for Command Complete 79 | 80 | const byte numChars = 4; //For uart reception 81 | char receivedChars[numChars]; // An array to store the received data from UART 82 | 83 | boolean newData = false; 84 | int Tally; 85 | int Pose; 86 | long TAngle; 87 | long ZAngle; 88 | long FAngle; 89 | long PAngle; 90 | char P1[2]; 91 | char P2[2]; 92 | char P3[2]; 93 | char P4[2]; 94 | char P5[2]; 95 | char P6[2]; 96 | char P7[2]; 97 | char P8[2]; 98 | char P9[2]; 99 | int ViscaPacketSize; 100 | int ViscaMove; 101 | int ViscaPanSpeed; 102 | int ViscaTiltSpeed; 103 | int ViscaFocusSpeed; 104 | int ViscaZoomSpeed; 105 | int Speed; //Generic holder for speed 106 | int PanSpeed; 107 | int TiltSpeed; 108 | int FocusSpeed; 109 | int ZoomSpeed; 110 | int PoseNumber; 111 | int PoseSpeed; 112 | const byte bufferSize = 11; 113 | char serialBuffer[bufferSize]; 114 | byte bufferIndex = 0; 115 | char EOL = '\n'; 116 | bool hasData = false; 117 | 118 | int IP1 = 0; 119 | int IP2 = 0; 120 | int IP3 = 0; 121 | int IP4 = 0; 122 | int IPGW = 0; 123 | int UDP = 0; 124 | int ViscaComand; 125 | int stopcheck; // For checking when a STOP command is received (0) 126 | int checksum; // For Calculating Checksum. Sum of the payload bytes (bytes 1 through 8) in the message 127 | int ByteNumber; // Counter for reading the serial buffer 128 | const char * returnIP; 129 | int returnPort; 130 | byte byteReceived[9]; 131 | int request = 0; 132 | char *payloadString; 133 | unsigned long entry; 134 | int IPCheck; 135 | 136 | String NumHex4; 137 | String NumHex5; 138 | String NumHex6; 139 | String NumHex7; 140 | String NumHex8; 141 | String NumHex9; 142 | String NumHex10; 143 | String NumHex11; 144 | String NumHex12; 145 | String NumHex13; 146 | String NumHex14; 147 | 148 | int PAngleIn; 149 | int TAngleIn; 150 | int ZAngleIn; 151 | int FAngleIn; 152 | void setup() { 153 | 154 | 155 | 156 | 157 | Serial.begin(115200); 158 | UARTport.begin(9600, SERIAL_8N1, 14, 15); 159 | 160 | while (IP1 != 192) { 161 | GetIP(); 162 | } 163 | // Select the IP address according to your local network 164 | IPAddress myIP(IP1, IP2, IP3, IP4); 165 | IPAddress myGW(IP1, IP2, IP3, IPGW); 166 | IPAddress myDNS(IP1, IP2, IP3, IPGW); 167 | IPAddress mySN(255, 255, 255, 0); 168 | Serial.print("\nIP address found from head set to " + String(IP1)); 169 | Serial.print("\nIP address found from head set to " + String(IP2)); 170 | Serial.print("\nIP address found from head set to " + String(IP3)); 171 | Serial.print("\nIP address found from head set to " + String(IP4)); 172 | while (!Serial); 173 | 174 | 175 | Serial.print("\nStarting UdpNTPClient on " + String(ARDUINO_BOARD)); 176 | Serial.println(" with " + String(SHIELD_TYPE)); 177 | Serial.println(WEBSERVER_WT32_ETH01_VERSION); 178 | 179 | 180 | WT32_ETH01_onEvent(); // To be called before ETH.begin() 181 | ETH.begin(ETH_PHY_ADDR, ETH_PHY_POWER); 182 | ETH.config(myIP, myGW, mySN, myDNS); 183 | WT32_ETH01_waitForConnect(); 184 | Udp.begin(localPort); 185 | 186 | 187 | 188 | 189 | } 190 | 191 | void loop() { 192 | //if (IPCheck==0){ 193 | // listenForUART(); 194 | //} 195 | 196 | // wait for a reply for UDP_TIMEOUT miliseconds 197 | unsigned long startMs = millis(); 198 | while (!Udp.available() && (millis() - startMs) < UDP_TIMEOUT) {} 199 | 200 | 201 | 202 | 203 | int packetSize = Udp.parsePacket(); // if there's data available, read a packet 204 | if (packetSize) { 205 | 206 | Udp.read(packetBuffer, NTP_PACKET_SIZE); 207 | Serial.println(); 208 | ViscaPacketSize = packetSize; 209 | 210 | 211 | Serial.print(", Last Paket count: "); 212 | Serial.println (ViscaPacketSize); 213 | Serial.print(packetBuffer[0]); 214 | Serial.print(", "); 215 | Serial.print(packetBuffer[1]); 216 | Serial.print(", "); 217 | Serial.print(packetBuffer[2]); 218 | Serial.print(", "); 219 | Serial.print(packetBuffer[3]); 220 | Serial.print(", "); 221 | Serial.print(packetBuffer[4]); 222 | Serial.print(", "); 223 | Serial.print(packetBuffer[5]); 224 | Serial.print(", "); 225 | Serial.print(packetBuffer[6]); 226 | Serial.print(", "); 227 | Serial.print(packetBuffer[7]); 228 | Serial.print(", "); 229 | Serial.print(packetBuffer[8]); 230 | Serial.println(""); 231 | Serial.print (packetBuffer[9]); 232 | Serial.print(", "); 233 | Serial.print(packetBuffer[10]); 234 | Serial.print(", "); 235 | Serial.print(packetBuffer[11]); 236 | Serial.print(", "); 237 | Serial.print(packetBuffer[12]); 238 | Serial.print(", "); 239 | Serial.print(packetBuffer[13]); 240 | Serial.print(", "); 241 | Serial.print(packetBuffer[14]); 242 | Serial.print(", "); 243 | Serial.print(packetBuffer[15]); 244 | Serial.print(", "); 245 | Serial.print(packetBuffer[16]); 246 | Serial.print(", "); 247 | Serial.print(packetBuffer[17]); 248 | Serial.println(""); 249 | 250 | 251 | 252 | 253 | //*********************Establish a DB move code fron the two packets before FF using Decimal Values******************** 254 | if (ViscaPacketSize == 5) { 255 | 256 | ViscaComand = packetBuffer[2] * 10 + (packetBuffer[3]); 257 | } 258 | if (ViscaPacketSize == 6) { 259 | ViscaComand = (packetBuffer[3] * 100 + (packetBuffer[4])); 260 | if ((packetBuffer[1] + packetBuffer[2] + packetBuffer[3]) == 14) { 261 | ViscaComand = 14; 262 | Tally = packetBuffer[4]; 263 | } 264 | if ((packetBuffer[1] + packetBuffer[2] + packetBuffer[3]) == 8) { 265 | ViscaComand = 137; 266 | PoseSpeed = packetBuffer[4]; 267 | } 268 | 269 | } 270 | 271 | if (ViscaPacketSize == 7) { 272 | if (ViscaComand = (packetBuffer[2] == 4)) { 273 | ViscaComand = (packetBuffer[2] * 10 + (packetBuffer[4])); 274 | PoseNumber = (packetBuffer[5]); 275 | } else { 276 | ViscaComand = packetBuffer[2]; 277 | }; 278 | if (ViscaComand == 40 || ViscaComand == 41 || ViscaComand == 42) { //If Command is a pose find out the pose requested 279 | Pose = (packetBuffer[5]); 280 | } 281 | 282 | } 283 | if (ViscaPacketSize == 8) { 284 | ViscaComand = (packetBuffer[2] * 10 + packetBuffer[4]); 285 | } 286 | if (ViscaPacketSize == 9) { 287 | ViscaComand = (packetBuffer[6] * 10 + packetBuffer[7]); 288 | PanSpeed = ((packetBuffer[4])); 289 | TiltSpeed = ((packetBuffer[5])); 290 | if (packetBuffer[3] == 71) { 291 | ViscaComand = 71; 292 | } 293 | } 294 | 295 | //For OBS padded commands 296 | if (ViscaPacketSize == 13) { 297 | ViscaComand = (packetBuffer[10] * 10 + packetBuffer[11]); // All 13 comands except the absolute position commands 298 | if (packetBuffer[1] + packetBuffer[2] + packetBuffer[3] == 76) { //Then Abolute zoom/Focus move requested eg vMix position 299 | ViscaComand = 76; 300 | NumHex4 = String(packetBuffer[4], HEX); 301 | NumHex5 = String(packetBuffer[5], HEX); 302 | NumHex6 = String(packetBuffer[6], HEX); 303 | NumHex7 = String(packetBuffer[7], HEX); 304 | NumHex8 = String(packetBuffer[8], HEX); 305 | NumHex9 = String(packetBuffer[9], HEX); 306 | NumHex10 = String(packetBuffer[10], HEX); 307 | NumHex11 = String(packetBuffer[11], HEX); 308 | } 309 | if (packetBuffer[1] + packetBuffer[2] + packetBuffer[3] == 77) { //Then Abolute Focus move requested eg vMix position 310 | ViscaComand = 77; 311 | } 312 | } 313 | if (ViscaPacketSize == 14) { 314 | ViscaComand = (packetBuffer[11] * 100 + packetBuffer[12]); 315 | 316 | } 317 | if (ViscaPacketSize == 15) { 318 | if (ViscaComand = (packetBuffer[10] == 4)) { 319 | ViscaComand = (packetBuffer[10] * 10 + packetBuffer[12]); 320 | PoseNumber = (packetBuffer[13]); 321 | } else { 322 | ViscaComand = packetBuffer[10]; 323 | } 324 | if (ViscaComand == 40 || 41 || 42) { //If Command is a pose find out the pose requested 325 | Pose = (packetBuffer[13]); 326 | } 327 | if (packetBuffer[1] + packetBuffer[2] + packetBuffer[3] == 9) { //Then Abolute move requested eg vMix position 328 | ViscaComand = 9; 329 | PanSpeed = packetBuffer[6]; 330 | TiltSpeed = packetBuffer[5]; 331 | NumHex7 = String(packetBuffer[7], HEX); 332 | NumHex8 = String(packetBuffer[8], HEX); 333 | NumHex9 = String(packetBuffer[9], HEX); 334 | NumHex10 = String(packetBuffer[10], HEX); 335 | NumHex11 = String(packetBuffer[11], HEX); 336 | NumHex12 = String(packetBuffer[12], HEX); 337 | NumHex13 = String(packetBuffer[13], HEX); 338 | NumHex14 = String(packetBuffer[14], HEX); 339 | } 340 | 341 | } 342 | 343 | 344 | if (ViscaPacketSize == 16) { 345 | ViscaComand = (packetBuffer[10] * 10 + packetBuffer[12]); 346 | } 347 | if (ViscaPacketSize == 17) { 348 | ViscaComand = (packetBuffer[14] * 10) + packetBuffer[15]; 349 | PanSpeed = ((packetBuffer[12])); 350 | TiltSpeed = ((packetBuffer[13])); 351 | } 352 | 353 | 354 | for ( int i = 0; i < ViscaPacketSize; ++i ) { //Clear the buffer 355 | packetBuffer[i] = (char)0; 356 | 357 | 358 | } 359 | 360 | 361 | 362 | //*******************Visca comands******************* 363 | 364 | //Udp.beginPacket(myGW, 1259); 365 | //Visca Returns requested at setup 366 | // if (ViscaComand == 78) { //Pant Tilt position request 367 | // Udp.write(PTposition, 11); 368 | // Serial.println ("PT position requested"); 369 | // delay(200); 370 | // } 371 | if (ViscaComand == 111) { //Zoom Position request 372 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 373 | Udp.write(ZoomPosition, 7); 374 | Udp.endPacket(); 375 | Serial.println ("Zoom position requested"); 376 | 377 | //delay(200); 378 | } 379 | if (ViscaComand == 112) { //Focus position request 380 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 381 | Udp.write(FocusPosition, 7); 382 | Udp.endPacket(); 383 | Serial.println ("Focus position requested"); 384 | //delay(200); 385 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 386 | Udp.write(Confirm, 3); 387 | Udp.endPacket(); 388 | Serial.println ("Confirm sent"); 389 | } 390 | 391 | 392 | 393 | 394 | 395 | } 396 | char buffer[50]; 397 | switch (ViscaComand) { 398 | 399 | case 3802: Serial.println ("AKA"); 400 | Udp.beginPacket(myGW, UDP); 401 | Udp.write(Confirm, 3); 402 | Udp.endPacket(); 403 | Serial.println ("Confirm sent"); 404 | break; 405 | 406 | case 14: Serial.println ("Tally light command:"); 407 | sprintf(buffer, "%d,%d\n", ViscaComand, Tally); 408 | UARTport.print(buffer); 409 | Serial.print (Tally); break; 410 | 411 | case 76: Serial.println ("Zoom/Focus Absolute position move request"); 412 | ReadInZoomFocus(); 413 | Serial.print("PanSpeed: "); 414 | Serial.println(PanSpeed); 415 | Serial.print("TiltSpeed: "); 416 | Serial.println(TiltSpeed); 417 | Serial.print("PAngleIn: "); 418 | Serial.println(PAngleIn); 419 | Serial.print("TAngleIn: "); 420 | Serial.println(TAngleIn); 421 | Serial.print("FAngleIn: "); 422 | Serial.println(FAngleIn); 423 | Serial.print("ZAngleIn: "); 424 | Serial.println(ZAngleIn); 425 | Serial.println("Sending vMix Absolute position request to PTZ head"); 426 | ViscaComand = 9; 427 | sprintf(buffer, "%d,%d,%d,%d,%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed, PAngleIn, TAngleIn, FAngleIn, ZAngleIn ); 428 | UARTport.print(buffer); 429 | break; 430 | 431 | case 77: Serial.println ("Focus Absolute position move request"); 432 | //Read in the Focus request here 433 | Udp.beginPacket(myGW, 1259); 434 | Udp.write(Confirm, 3); 435 | Udp.endPacket(); 436 | Serial.println ("Confirm sent"); 437 | break; 438 | 439 | case 9: Serial.println ("PT Absolute position move request from vMix"); 440 | ReadInPTpos(); 441 | sprintf(buffer, "%d,%d,%d,%d,%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed, PAngleIn, TAngleIn, FAngleIn, ZAngleIn ); 442 | UARTport.print(buffer); break; 443 | break; 444 | 445 | case 5603: Serial.println("Manual focus"); 446 | Udp.beginPacket(myGW, 1259); 447 | Udp.write(Confirm, 3); 448 | Udp.endPacket(); 449 | Serial.println ("Confirm sent"); 450 | break; 451 | 452 | case 71: ("Send focus home"); 453 | Udp.beginPacket(myGW, 1259); 454 | Udp.write(Confirm, 3); 455 | Udp.endPacket(); break; 456 | 457 | case 78: Serial.println ("PT position requested1"); 458 | sprintf(buffer, "%d\n", ViscaComand ); 459 | UARTport.print(buffer); //Send request to PTZ head 460 | int Request; 461 | if (Request = 0) { 462 | Serial.println ("CHECKING FOR UART reply"); 463 | listenForUART(); 464 | Serial.print("PAngle: "); 465 | Serial.println(PAngle); 466 | Serial.print("TAngle: "); 467 | Serial.println(TAngle); 468 | Serial.print("ZAngle: "); 469 | Serial.println(ZAngle); 470 | Serial.print("FAngle: "); 471 | Serial.println(FAngle); 472 | Serial.println(PTposition[0]); 473 | Serial.println(PTposition[1]); 474 | Serial.println(PTposition[10]); 475 | 476 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 477 | Udp.write(PTposition, 11); 478 | Udp.endPacket(); 479 | //delay(200); 480 | Request = 2; 481 | } else { 482 | //PTposition[2] = 0x00; PTposition[3] = 0x05; PTposition[4] = 0x02; PTposition[5] = 0x0E; PTposition[6] = 0x0F; break; 483 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 484 | Udp.write(PTposition, 11); 485 | Udp.endPacket(); 486 | //delay(200); 487 | Request = 0; 488 | Serial.println(PTposition[0] ); 489 | Serial.println(PTposition[1]); 490 | Serial.println(PTposition[2]); 491 | Serial.println(PTposition[3]); 492 | Serial.println(PTposition[4]); 493 | Serial.println(PTposition[5]); 494 | Serial.println(PTposition[6]); 495 | Serial.println(PTposition[7]); 496 | Serial.println(PTposition[8]); 497 | Serial.println(PTposition[9]); 498 | Serial.println(PTposition[10]); 499 | Serial.println(PTposition[11]); 500 | } 501 | break; 502 | 503 | 504 | 505 | 506 | case 64: Serial.print(", PT Home "); 507 | sprintf(buffer, "%d\n", ViscaComand ); 508 | UARTport.print(buffer); break; 509 | 510 | 511 | 512 | 513 | case 33: Serial.print(", PT Stop "); 514 | sprintf(buffer, "%d\n", ViscaComand ); 515 | UARTport.print(buffer); 516 | delay(20); 517 | listenForUART(); 518 | Serial.print("IP4 "); 519 | Serial.print(IP4); 520 | break; 521 | 522 | case 700: Serial.print(", Zoom Stop "); 523 | sprintf(buffer, "%d\n", ViscaComand ); 524 | UARTport.print(buffer); 525 | delay(20); 526 | listenForUART(); 527 | break; 528 | 529 | case 800: Serial.print(", Focus Stop 1 "); 530 | Serial.print(ViscaComand); 531 | sprintf(buffer, "%d\n", ViscaComand ); 532 | UARTport.print(buffer); 533 | delay(20); 534 | listenForUART(); 535 | break; 536 | case 13: Serial.print(", Pan Left "); 537 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 538 | UARTport.print(buffer); break; 539 | 540 | 541 | case 23: Serial.print(", Pan Right "); 542 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 543 | UARTport.print(buffer); break; 544 | 545 | case 31: Serial.print(", Tilt Up "); 546 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 547 | UARTport.print(buffer); break; 548 | 549 | case 32: Serial.print(", Tilt Down "); 550 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 551 | UARTport.print(buffer); break; 552 | 553 | case 11: Serial.print(", Up Left "); 554 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 555 | UARTport.print(buffer); break; 556 | 557 | case 21: Serial.print(", Up Right "); 558 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 559 | UARTport.print(buffer); break; 560 | 561 | case 12: Serial.print(", Down Left "); 562 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 563 | UARTport.print(buffer); break; 564 | 565 | case 22: Serial.print(", Down Right "); 566 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 567 | UARTport.print(buffer); break; 568 | 569 | case 748: Serial.print(", Zoom out p1 "); 570 | sprintf(buffer, "%d\n", ViscaComand ); 571 | UARTport.print(buffer); break; 572 | 573 | case 749: Serial.print(", Zoom out p2 "); 574 | sprintf(buffer, "%d\n", ViscaComand ); 575 | UARTport.print(buffer); break; 576 | 577 | case 750: Serial.print(", Zoom out p3 "); 578 | sprintf(buffer, "%d\n", ViscaComand ); 579 | UARTport.print(buffer); break; 580 | 581 | case 751: Serial.print(", Zoom out p4 "); 582 | sprintf(buffer, "%d\n", ViscaComand ); 583 | UARTport.print(buffer); break; 584 | 585 | case 752: Serial.print(", Zoom out p5 "); 586 | sprintf(buffer, "%d\n", ViscaComand ); 587 | UARTport.print(buffer); break; 588 | 589 | case 753: Serial.print(", Zoom out p6 "); 590 | sprintf(buffer, "%d\n", ViscaComand ); 591 | UARTport.print(buffer); break; 592 | 593 | case 754: Serial.print(", Zoom out p7 "); 594 | sprintf(buffer, "%d\n", ViscaComand ); 595 | UARTport.print(buffer); break; 596 | 597 | case 755: Serial.print(", Zoom out p8 "); 598 | sprintf(buffer, "%d\n", ViscaComand ); 599 | UARTport.print(buffer); break; 600 | 601 | case 756: Serial.print(", Zoom out p9 "); 602 | sprintf(buffer, "%d\n", ViscaComand ); 603 | UARTport.print(buffer); break; 604 | 605 | case 732: Serial.print(", Zoom in p1 "); 606 | sprintf(buffer, "%d\n", ViscaComand ); 607 | UARTport.print(buffer); break; 608 | 609 | case 733: Serial.print(", Zoom in p2 "); 610 | sprintf(buffer, "%d\n", ViscaComand ); 611 | UARTport.print(buffer); break; 612 | 613 | case 734: Serial.print(", Zoom in p3 "); 614 | sprintf(buffer, "%d\n", ViscaComand ); 615 | UARTport.print(buffer); break; 616 | 617 | case 735: Serial.print(", Zoom in p4 "); 618 | sprintf(buffer, "%d\n", ViscaComand ); 619 | UARTport.print(buffer); break; 620 | 621 | case 736: Serial.print(", Zoom in p5 "); 622 | sprintf(buffer, "%d\n", ViscaComand ); 623 | UARTport.print(buffer); break; 624 | 625 | case 737: Serial.print(", Zoom in p6 "); 626 | sprintf(buffer, "%d\n", ViscaComand ); 627 | UARTport.print(buffer); break; 628 | 629 | case 738: Serial.print(", Zoom in p7 "); 630 | sprintf(buffer, "%d\n", ViscaComand ); 631 | UARTport.print(buffer); break; 632 | 633 | case 739: Serial.print(", Zoom in p8 "); 634 | sprintf(buffer, "%d\n", ViscaComand ); 635 | UARTport.print(buffer); break; 636 | 637 | case 2402: Serial.print(", Focus Stop "); 638 | Serial.print(ViscaComand); 639 | sprintf(buffer, "%d\n", ViscaComand ); 640 | UARTport.print(buffer); 641 | delay(20); 642 | listenForUART(); 643 | break; 644 | case 832: Serial.print(", Focus Near p1 "); 645 | sprintf(buffer, "%d\n", ViscaComand ); 646 | UARTport.print(buffer); break; 647 | 648 | case 833: Serial.print(", Focus Near p2 "); 649 | sprintf(buffer, "%d\n", ViscaComand ); 650 | UARTport.print(buffer); break; 651 | 652 | case 834: Serial.print(", Focus Near p3 "); 653 | sprintf(buffer, "%d\n", ViscaComand ); 654 | UARTport.print(buffer); break; 655 | 656 | case 835: Serial.print(", Focus Near p4 "); 657 | sprintf(buffer, "%d\n", ViscaComand ); 658 | UARTport.print(buffer); break; 659 | 660 | case 836: Serial.print(", Focus Near p5 "); 661 | sprintf(buffer, "%d\n", ViscaComand ); 662 | UARTport.print(buffer); break; 663 | 664 | case 837: Serial.print(", Focus Near p6 "); 665 | sprintf(buffer, "%d\n", ViscaComand ); 666 | UARTport.print(buffer); break; 667 | 668 | case 838: Serial.print(", Focus Near p7 "); 669 | sprintf(buffer, "%d\n", ViscaComand ); 670 | UARTport.print(buffer); break; 671 | 672 | case 839: Serial.print(", Focus Near p8 "); 673 | sprintf(buffer, "%d\n", ViscaComand ); 674 | UARTport.print(buffer); break; 675 | 676 | case 848: Serial.print(", Focus Far p1 "); 677 | sprintf(buffer, "%d\n", ViscaComand ); 678 | UARTport.print(buffer); break; 679 | 680 | case 849: Serial.print(", Focus Far p2 "); 681 | sprintf(buffer, "%d\n", ViscaComand ); 682 | UARTport.print(buffer); break; 683 | 684 | case 850: Serial.print(", Focus Far p3 "); 685 | sprintf(buffer, "%d\n", ViscaComand ); 686 | UARTport.print(buffer); break; 687 | 688 | case 851: Serial.print(", Focus Far p4 "); 689 | sprintf(buffer, "%d\n", ViscaComand ); 690 | UARTport.print(buffer); break; 691 | 692 | case 852: Serial.print(", Focus Far p5 "); 693 | sprintf(buffer, "%d\n", ViscaComand ); 694 | UARTport.print(buffer); break; 695 | 696 | case 853: Serial.print(", Focus Far p6 "); 697 | sprintf(buffer, "%d\n", ViscaComand ); 698 | UARTport.print(buffer); break; 699 | 700 | case 854: Serial.print(", Focus Far p7 "); 701 | sprintf(buffer, "%d\n", ViscaComand ); 702 | UARTport.print(buffer); break; 703 | 704 | case 855: Serial.print(", Focus Far p8 "); 705 | sprintf(buffer, "%d\n", ViscaComand ); 706 | UARTport.print(buffer); break; 707 | 708 | case 4901: Serial.print(", Ramp/EaseValue=1 "); 709 | sprintf(buffer, "%d\n", ViscaComand ); 710 | UARTport.print(buffer); break; 711 | 712 | case 4902: Serial.print(", Ramp/EaseValue=2 "); 713 | sprintf(buffer, "%d\n", ViscaComand ); 714 | UARTport.print(buffer); break; 715 | 716 | case 4903: Serial.print(", Ramp/EaseValue=3 "); 717 | sprintf(buffer, "%d\n", ViscaComand ); 718 | UARTport.print(buffer); break; 719 | 720 | case 2: Serial.print(", Start Recore "); 721 | sprintf(buffer, "%d\n", ViscaComand ); 722 | UARTport.print(buffer); break; 723 | 724 | case 3: Serial.print(", Stop Record "); 725 | sprintf(buffer, "%d\n", ViscaComand ); 726 | UARTport.print(buffer); break; 727 | 728 | case 41: Serial.print(", Save Pose "); 729 | Serial.print(Pose); 730 | sprintf(buffer, "%d,%d\n", ViscaComand, Pose ); 731 | UARTport.print(buffer); break; 732 | 733 | case 42: Serial.print(", Move to pose "); 734 | Serial.print(Pose); 735 | sprintf(buffer, "%d,%d\n", ViscaComand, Pose ); 736 | UARTport.print(buffer); break; 737 | 738 | case 40: Serial.print(", Reset Pose do Defaults "); 739 | Serial.print(Pose); 740 | sprintf(buffer, "%d,%d\n", ViscaComand, Pose ); 741 | UARTport.print(buffer); break; 742 | 743 | 744 | case 126: Serial.print(", Record Mode setting "); 745 | sprintf(buffer, "%d\n", ViscaComand ); 746 | UARTport.print(buffer); break; 747 | 748 | case 137: Serial.print(", Pose speed "); 749 | sprintf(buffer, "%d,%d\n", ViscaComand, PoseSpeed ); 750 | UARTport.print(buffer); break; 751 | 752 | 753 | 754 | 755 | } 756 | ViscaComand = 0; //Clear the Comand ready to start fresh 757 | } 758 | void listenForUART() { 759 | //Serial.println ("Listening"); 760 | char buffer[30]; 761 | int PP = 78; 762 | int TT = 79; 763 | int ZZ = 80; 764 | int FF = 81; 765 | int SYS1 = 665; 766 | int SYS2 = 666; 767 | int SYS3 = 667; 768 | int SYS4 = 668; 769 | int SYS5 = 669; 770 | 771 | static byte ndx = 0; 772 | char endMarker = '\n'; 773 | char rc; 774 | 775 | sprintf(buffer, "%d\n", PP );//First Pass get PP 776 | UARTport.print(buffer); 777 | UARTport.flush(); 778 | newData = false; 779 | delay(50); 780 | GetUARTdata(); 781 | if (newData == true) { 782 | PAngle = atoi(receivedChars); 783 | PAngle = PAngle * 2; 784 | //PAngle = 10 * ((PAngle + 5) / 10); //Round to nearest 10 785 | 786 | // if (PAngle < 0) { 787 | // PAngle = abs(PAngle) + 1000; 788 | // } 789 | Serial.print("\n"); 790 | Serial.print("PAngle: "); 791 | Serial.println(PAngle); 792 | if (PAngle < 0) { 793 | Serial.print("PAngle is negative "); 794 | } else { 795 | Serial.print("PAngle is Posative "); 796 | } 797 | } 798 | 799 | sprintf(buffer, "%d\n", TT ); //Second pass get TT 800 | delay(100); 801 | UARTport.print(buffer); 802 | UARTport.flush(); 803 | newData = false; 804 | delay(50); 805 | GetUARTdata(); 806 | if (newData == true) { 807 | TAngle = atoi(receivedChars) * 2; 808 | //TAngle = 10 * ((TAngle + 5) / 10); //Round to nearest 10 809 | // if (TAngle < 0) { 810 | // TAngle = abs(TAngle) + 1000; 811 | // } 812 | Serial.print("TAngle: "); 813 | Serial.println(TAngle); 814 | } 815 | 816 | sprintf(buffer, "%d\n", FF ); //Third pass get FF 817 | delay(100); 818 | UARTport.print(buffer); 819 | UARTport.flush(); 820 | newData = false; 821 | delay(50); 822 | GetUARTdata(); 823 | if (newData == true) { 824 | FAngle = atoi(receivedChars); 825 | FAngle = abs(FAngle); 826 | Serial.print("FAngle=: "); //This gets past back to VISCA position save 827 | Serial.println(FAngle); 828 | } 829 | 830 | sprintf(buffer, "%d\n", ZZ ); //Forth pass get ZZ 831 | delay(100); 832 | UARTport.print(buffer); 833 | UARTport.flush(); 834 | newData = false; 835 | delay(50); 836 | GetUARTdata(); 837 | if (newData == true) { 838 | ZAngle = atoi(receivedChars); 839 | ZAngle = abs(ZAngle); 840 | Serial.print("ZAngle: "); 841 | Serial.println(ZAngle); 842 | } 843 | //Convert to uint8 for output 844 | 845 | 846 | if (PAngle > 0) { 847 | PAngle = PAngle * 117.95; //divisions reduced from norm to make establisheing sign of value easier 848 | } else { 849 | PAngle = PAngle * 235.9; 850 | } 851 | 852 | TAngle = TAngle * 235.9; 853 | 854 | Serial.print("PAngle: "); 855 | Serial.println(PAngle); 856 | if (PAngle < 0) { 857 | Serial.print("PAngle is negative "); 858 | } else { 859 | Serial.print("PAngle is Posative "); 860 | } 861 | if (PAngle < 0) { //If Pangle negative 862 | PTposition[2] = {0x0F}; 863 | Serial.print("PAngle negative"); 864 | } else { 865 | PTposition[2] = {0x00}; 866 | } 867 | 868 | 869 | // Solve for Pan 870 | 871 | for (int8_t i = 8; i > 0; i--) { 872 | if (i - 2 > 2) { 873 | PTposition[i - 2] = PAngle % 16; //Add it to the Array 874 | } 875 | PAngle = (PAngle - PTposition[i - 2]) / 16; //Process the next part 876 | 877 | if ( PTposition[2] == 0x0F) { //If We are processing a negative angle striff off the F for VISCA 878 | switch (PTposition[i - 2]) { 879 | case 0x00: PTposition[i - 2] = 0x0F; break; 880 | case 0xF1: PTposition[i - 2] = 0x01; break; 881 | case 0xF2: PTposition[i - 2] = 0x02; break; 882 | case 0xF3: PTposition[i - 2] = 0x03; break; 883 | case 0xF4: PTposition[i - 2] = 0x04; break; 884 | case 0xF5: PTposition[i - 2] = 0x05; break; 885 | case 0xF6: PTposition[i - 2] = 0x06; break; 886 | case 0xF7: PTposition[i - 2] = 0x07; break; 887 | case 0xF8: PTposition[i - 2] = 0x08; break; 888 | case 0xF9: PTposition[i - 2] = 0x09; break; 889 | case 0xFA: PTposition[i - 2] = 0x0A; break; 890 | case 0xFB: PTposition[i - 2] = 0x0B; break; 891 | case 0xFC: PTposition[i - 2] = 0x0C; break; 892 | case 0xFD: PTposition[i - 2] = 0x0D; break; 893 | case 0xFE: PTposition[i - 2] = 0x0E; break; 894 | case 0xFF: PTposition[i - 2] = 0x0F; break; 895 | } 896 | } 897 | } 898 | 899 | 900 | // Solve for Tilt ****Tilt isstamping F on position2 Fix 901 | for (int8_t i = 12; i > 0; i--) { 902 | if (i - 2 > 6) { 903 | PTposition[i - 2] = TAngle % 16; 904 | } 905 | TAngle = (TAngle - PTposition[i - 2]) / 16; 906 | if ( TAngle < 0) { //If We are processing a negative angle striff off the F for VISCA 907 | switch (PTposition[i - 2]) { 908 | case 0xF1: PTposition[i - 2] = 0x01; break; 909 | case 0xF2: PTposition[i - 2] = 0x02; break; 910 | case 0xF3: PTposition[i - 2] = 0x03; break; 911 | case 0xF4: PTposition[i - 2] = 0x04; break; 912 | case 0xF5: PTposition[i - 2] = 0x05; break; 913 | case 0xF6: PTposition[i - 2] = 0x06; break; 914 | case 0xF7: PTposition[i - 2] = 0x07; break; 915 | case 0xF8: PTposition[i - 2] = 0x08; break; 916 | case 0xF9: PTposition[i - 2] = 0x09; break; 917 | case 0xFA: PTposition[i - 2] = 0x0A; break; 918 | case 0xFB: PTposition[i - 2] = 0x0B; break; 919 | case 0xFC: PTposition[i - 2] = 0x0C; break; 920 | case 0xFD: PTposition[i - 2] = 0x0D; break; 921 | case 0xFE: PTposition[i - 2] = 0x0E; break; 922 | case 0xFF: PTposition[i - 2] = 0x0F; break; 923 | } 924 | } 925 | 926 | } 927 | 928 | Serial.print("PTpos0: "); 929 | Serial.println(PTposition[0]); 930 | Serial.print("PTpos1: "); 931 | Serial.println(PTposition[1]); 932 | Serial.print("PTpos2: "); 933 | Serial.println(PTposition[2]); 934 | Serial.print("PTpos3: "); 935 | Serial.println(PTposition[3]); 936 | Serial.print("PTpos4: "); 937 | Serial.println(PTposition[4]); 938 | Serial.print("PTpos5: "); 939 | Serial.println(PTposition[5]); 940 | Serial.print("PTpos6: "); 941 | Serial.println(PTposition[6]); 942 | Serial.print("PTpos7: "); 943 | Serial.println(PTposition[7]); 944 | Serial.print("PTpos8: "); 945 | Serial.println(PTposition[8]); 946 | Serial.print("PTpos9: "); 947 | Serial.println(PTposition[9]); 948 | Serial.print("PTpos10: "); 949 | Serial.println(PTposition[10]); 950 | Serial.print("PTpos11: "); 951 | Serial.println(PTposition[11]); //Closing termonator 952 | 953 | // Solve for Focus 954 | 955 | FAngle = ((FAngle * 604.5) + 1000); //Because the Focus range is 1000-61440 956 | 957 | for (int8_t i = 7; i > 0; i--) { 958 | if (i - 2 > 1) { 959 | FocusPosition[i - 2] = FAngle % 16; //Add it to the Array 960 | } 961 | FAngle = (FAngle - FocusPosition[i - 2]) / 16; //Process the next part 962 | } 963 | Serial.print("Fpos0: "); 964 | Serial.println(FocusPosition[0]); 965 | Serial.print("Fpos1: "); 966 | Serial.println(FocusPosition[1]); 967 | Serial.print("Fpos2: "); 968 | Serial.println(FocusPosition[2]); 969 | Serial.print("Fpos3: "); 970 | Serial.println(FocusPosition[3]); 971 | Serial.print("Fpos4: "); 972 | Serial.println(FocusPosition[4]); 973 | Serial.print("Fpos5: "); 974 | Serial.println(FocusPosition[5]); 975 | Serial.print("Fpos6 -Should be 255: "); 976 | Serial.println(FocusPosition[6]); 977 | 978 | 979 | 980 | 981 | // Solve for Zoom 982 | 983 | ZAngle = (ZAngle * 60); //Because the zoom range is 0-6000 984 | 985 | for (int8_t i = 7; i > 0; i--) { 986 | if (i - 2 > 1) { 987 | ZoomPosition[i - 2] = ZAngle % 16; //Add it to the Array 988 | } 989 | ZAngle = (ZAngle - ZoomPosition[i - 2]) / 16; //Process the next part 990 | } 991 | ZoomPosition[6] = {0xFF}; 992 | Serial.print("ZPos0: "); 993 | Serial.println(ZoomPosition[0]); 994 | Serial.print("ZPos1: "); 995 | Serial.println(ZoomPosition[1]); 996 | Serial.print("ZPos2: "); 997 | Serial.println(ZoomPosition[2]); 998 | Serial.print("ZPos3: "); 999 | Serial.println(ZoomPosition[3]); 1000 | Serial.print("ZPos4: "); 1001 | Serial.println(ZoomPosition[4]); 1002 | Serial.print("ZPos5: "); 1003 | Serial.println(ZoomPosition[5]); 1004 | Serial.print("ZPos6 should be 255: "); 1005 | Serial.println(ZoomPosition[6]); 1006 | 1007 | 1008 | 1009 | 1010 | // switch (PAngle) { 1011 | // //Left 1012 | // case 0: PTposition[2] = 0x00; PTposition[3] = 0x00; PTposition[4] = 0x00; PTposition[5] = 0x00; PTposition[6] = 0x00; break; 1013 | // case 10: PTposition[2] = 0x00; PTposition[3] = 0x00; PTposition[4] = 0x09; PTposition[5] = 0x03; PTposition[6] = 0x07; break; 1014 | // case 20: PTposition[2] = 0x00; PTposition[3] = 0x01; PTposition[4] = 0x02; PTposition[5] = 0x06; PTposition[6] = 0x0E; break; 1015 | // case 30: PTposition[2] = 0x00; PTposition[3] = 0x01; PTposition[4] = 0x0B; PTposition[5] = 0x0A; PTposition[6] = 0x05; break; 1016 | // case 40: PTposition[2] = 0x00; PTposition[3] = 0x02; PTposition[4] = 0x04; PTposition[5] = 0x0D; PTposition[6] = 0x0C; break; 1017 | // case 50: PTposition[2] = 0x00; PTposition[3] = 0x02; PTposition[4] = 0x0E; PTposition[5] = 0x01; PTposition[6] = 0x03; break; 1018 | // case 60: PTposition[2] = 0x00; PTposition[3] = 0x03; PTposition[4] = 0x07; PTposition[5] = 0x04; PTposition[6] = 0x0A; break; 1019 | // case 70: PTposition[2] = 0x00; PTposition[3] = 0x04; PTposition[4] = 0x00; PTposition[5] = 0x08; PTposition[6] = 0x01; break; 1020 | // case 80: PTposition[2] = 0x00; PTposition[3] = 0x04; PTposition[4] = 0x09; PTposition[5] = 0x0B; PTposition[6] = 0x08; break; 1021 | // case 90: PTposition[2] = 0x00; PTposition[3] = 0x05; PTposition[4] = 0x02; PTposition[5] = 0x0E; PTposition[6] = 0x0F; break; 1022 | // case 100: PTposition[2] = 0x00; PTposition[3] = 0x05; PTposition[4] = 0x0C; PTposition[5] = 0x02; PTposition[6] = 0x06; break; 1023 | // case 110: PTposition[2] = 0x00; PTposition[3] = 0x00; PTposition[4] = 0x09; PTposition[5] = 0x03; PTposition[6] = 0x07; break; 1024 | // case 120: PTposition[2] = 0x00; PTposition[3] = 0x06; PTposition[4] = 0x0E; PTposition[5] = 0x09; PTposition[6] = 0x04; break; 1025 | // case 130: PTposition[2] = 0x00; PTposition[3] = 0x07; PTposition[4] = 0x07; PTposition[5] = 0x0C; PTposition[6] = 0x0B; break; 1026 | // case 140: PTposition[2] = 0x00; PTposition[3] = 0x08; PTposition[4] = 0x01; PTposition[5] = 0x00; PTposition[6] = 0x02; break; 1027 | // case 150: PTposition[2] = 0x00; PTposition[3] = 0x08; PTposition[4] = 0x0A; PTposition[5] = 0x03; PTposition[6] = 0x09; break; 1028 | // case 160: PTposition[2] = 0x00; PTposition[3] = 0x09; PTposition[4] = 0x03; PTposition[5] = 0x07; PTposition[6] = 0x00; break; 1029 | // case 169: PTposition[2] = 0x00; PTposition[3] = 0x09; PTposition[4] = 0x0B; PTposition[5] = 0x0B; PTposition[6] = 0x0B; break; 1030 | // case 170: PTposition[2] = 0x00; PTposition[3] = 0x09; PTposition[4] = 0x0C; PTposition[5] = 0x0A; PTposition[6] = 0x07; break; 1031 | // // //Right 1032 | // case 1010: PTposition[2] = 0x0F; PTposition[3] = 0x0F; PTposition[4] = 0x06; PTposition[5] = 0x0C; PTposition[6] = 0x09; break; 1033 | // case 1020: PTposition[2] = 0x0F; PTposition[3] = 0x0E; PTposition[4] = 0x0D; PTposition[5] = 0x09; PTposition[6] = 0x02; break; 1034 | // case 1030: PTposition[2] = 0x0F; PTposition[3] = 0x0E; PTposition[4] = 0x04; PTposition[5] = 0x05; PTposition[6] = 0x0B; break; 1035 | // case 1040: PTposition[2] = 0x0F; PTposition[3] = 0x0D; PTposition[4] = 0x0B; PTposition[5] = 0x02; PTposition[6] = 0x04; break; 1036 | // case 1050: PTposition[2] = 0x0F; PTposition[3] = 0x0D; PTposition[4] = 0x01; PTposition[5] = 0x0E; PTposition[6] = 0x0D; break; 1037 | // case 1060: PTposition[2] = 0x0F; PTposition[3] = 0x0C; PTposition[4] = 0x08; PTposition[5] = 0x0B; PTposition[6] = 0x06; break; 1038 | // case 1070: PTposition[2] = 0x0F; PTposition[3] = 0x0B; PTposition[4] = 0x0F; PTposition[5] = 0x07; PTposition[6] = 0x0F; break; 1039 | // case 1080: PTposition[2] = 0x0F; PTposition[3] = 0x0B; PTposition[4] = 0x06; PTposition[5] = 0x04; PTposition[6] = 0x08; break; 1040 | // case 1090: PTposition[2] = 0x0F; PTposition[3] = 0x0A; PTposition[4] = 0x0D; PTposition[5] = 0x01; PTposition[6] = 0x01; break; 1041 | // case 1100: PTposition[2] = 0x0F; PTposition[3] = 0x0A; PTposition[4] = 0x03; PTposition[5] = 0x0D; PTposition[6] = 0x0A; break; 1042 | // case 1110: PTposition[2] = 0x0F; PTposition[3] = 0x09; PTposition[4] = 0x0A; PTposition[5] = 0x0A; PTposition[6] = 0x03; break; 1043 | // case 1120: PTposition[2] = 0x0F; PTposition[3] = 0x09; PTposition[4] = 0x01; PTposition[5] = 0x06; PTposition[6] = 0x0C; break; 1044 | // case 1130: PTposition[2] = 0x0F; PTposition[3] = 0x08; PTposition[4] = 0x08; PTposition[5] = 0x03; PTposition[6] = 0x05; break; 1045 | // case 1140: PTposition[2] = 0x0F; PTposition[3] = 0x07; PTposition[4] = 0x0E; PTposition[5] = 0x0F; PTposition[6] = 0x0E; break; 1046 | // case 1150: PTposition[2] = 0x0F; PTposition[3] = 0x07; PTposition[4] = 0x05; PTposition[5] = 0x0C; PTposition[6] = 0x07; break; 1047 | // case 1160: PTposition[2] = 0x0F; PTposition[3] = 0x06; PTposition[4] = 0x0C; PTposition[5] = 0x09; PTposition[6] = 0x00; break; 1048 | // case 1169: PTposition[2] = 0x0F; PTposition[3] = 0x06; PTposition[4] = 0x04; PTposition[5] = 0x04; PTposition[6] = 0x05; break; 1049 | // case 1170: PTposition[2] = 0x0F; PTposition[3] = 0x06; PTposition[4] = 0x03; PTposition[5] = 0x05; PTposition[6] = 0x09; break; 1050 | // } 1051 | // 1052 | // switch (TAngle) { 1053 | // // //UP 1054 | // case 0: PTposition[7] = 0x00; PTposition[8] = 0x00; PTposition[9] = 0x00; PTposition[10] = 0x00; break; 1055 | // case 10: PTposition[7] = 0x00; PTposition[8] = 0x09; PTposition[9] = 0x03; PTposition[10] = 0x07; break; 1056 | // case 20: PTposition[7] = 0x01; PTposition[8] = 0x02; PTposition[9] = 0x06; PTposition[10] = 0x0E; break; 1057 | // case 30: PTposition[7] = 0x01; PTposition[8] = 0x0B; PTposition[9] = 0x0A; PTposition[10] = 0x05; break; 1058 | // case 40: PTposition[7] = 0x02; PTposition[8] = 0x04; PTposition[9] = 0x0D; PTposition[10] = 0x0C; break; 1059 | // case 50: PTposition[7] = 0x02; PTposition[8] = 0x0E; PTposition[9] = 0x01; PTposition[10] = 0x03; break; 1060 | // case 60: PTposition[7] = 0x03; PTposition[8] = 0x07; PTposition[9] = 0x04; PTposition[10] = 0x0A; break; 1061 | // case 70: PTposition[7] = 0x04; PTposition[8] = 0x00; PTposition[9] = 0x08; PTposition[10] = 0x01; break; 1062 | // case 80: PTposition[7] = 0x04; PTposition[8] = 0x09; PTposition[9] = 0x0B; PTposition[10] = 0x08; break; 1063 | // case 90: PTposition[7] = 0x05; PTposition[8] = 0x02; PTposition[9] = 0x0E; PTposition[10] = 0x0F; break; 1064 | // // //Down 1065 | // case 1010: PTposition[7] = 0x0F; PTposition[8] = 0x06; PTposition[9] = 0x0C; PTposition[10] = 0x09; break; 1066 | // case 1020: PTposition[7] = 0x0E; PTposition[8] = 0x0D; PTposition[9] = 0x09; PTposition[10] = 0x02; break; 1067 | // case 1030: PTposition[7] = 0x0E; PTposition[8] = 0x04; PTposition[9] = 0x05; PTposition[10] = 0x0B; break; 1068 | // 1069 | // } 1070 | // 1071 | // switch (FAngle) { 1072 | // // //UP 1073 | // case 0: PTposition[7] = 0x00; PTposition[8] = 0x00; PTposition[9] = 0x00; PTposition[10] = 0x00; break; 1074 | // case 10: PTposition[7] = 0x00; PTposition[8] = 0x09; PTposition[9] = 0x03; PTposition[10] = 0x07; break; 1075 | // case 20: PTposition[7] = 0x01; PTposition[8] = 0x02; PTposition[9] = 0x06; PTposition[10] = 0x0E; break; 1076 | // case 30: PTposition[7] = 0x01; PTposition[8] = 0x0B; PTposition[9] = 0x0A; PTposition[10] = 0x05; break; 1077 | // case 40: PTposition[7] = 0x02; PTposition[8] = 0x04; PTposition[9] = 0x0D; PTposition[10] = 0x0C; break; 1078 | // case 50: PTposition[7] = 0x02; PTposition[8] = 0x0E; PTposition[9] = 0x01; PTposition[10] = 0x03; break; 1079 | // case 60: PTposition[7] = 0x03; PTposition[8] = 0x07; PTposition[9] = 0x04; PTposition[10] = 0x0A; break; 1080 | // case 70: PTposition[7] = 0x04; PTposition[8] = 0x00; PTposition[9] = 0x08; PTposition[10] = 0x01; break; 1081 | // case 80: PTposition[7] = 0x04; PTposition[8] = 0x09; PTposition[9] = 0x0B; PTposition[10] = 0x08; break; 1082 | // case 90: PTposition[7] = 0x05; PTposition[8] = 0x02; PTposition[9] = 0x0E; PTposition[10] = 0x0F; break; 1083 | // // //Down 1084 | // case 1010: PTposition[7] = 0x0F; PTposition[8] = 0x06; PTposition[9] = 0x0C; PTposition[10] = 0x09; break; 1085 | // case 1020: PTposition[7] = 0x0E; PTposition[8] = 0x0D; PTposition[9] = 0x09; PTposition[10] = 0x02; break; 1086 | // case 1030: PTposition[7] = 0x0E; PTposition[8] = 0x04; PTposition[9] = 0x05; PTposition[10] = 0x0B; break; 1087 | // 1088 | // } 1089 | 1090 | 1091 | 1092 | 1093 | 1094 | } 1095 | 1096 | 1097 | void GetUARTdata() { 1098 | static byte ndx = 0; 1099 | char endMarker = '\n'; 1100 | char rc; 1101 | 1102 | while (UARTport.available() ) { 1103 | rc = UARTport.read(); 1104 | if (rc != endMarker) { 1105 | receivedChars[ndx] = rc; 1106 | ndx++; 1107 | if (ndx > numChars) { 1108 | ndx = numChars - 1; 1109 | } 1110 | } 1111 | else { 1112 | receivedChars[ndx] = '\0'; // terminate the string 1113 | ndx = 0; 1114 | newData = true; 1115 | } 1116 | } 1117 | } 1118 | 1119 | 1120 | //At startup get the current IP adress from rthe main processor 1121 | void GetIP() { 1122 | Serial.println ("Listening"); 1123 | char buffer[30]; 1124 | delay(500); 1125 | int SYS1 = 665; 1126 | int SYS2 = 666; 1127 | int SYS3 = 667; 1128 | int SYS4 = 668; 1129 | int SYS5 = 669; 1130 | int SYS6 = 670; 1131 | static byte ndx = 0; 1132 | char endMarker = '\n'; 1133 | char rc; 1134 | 1135 | sprintf(buffer, "%d\n", SYS1 ); //Gget IP1 1136 | UARTport.print(buffer); 1137 | UARTport.flush(); 1138 | newData = false; 1139 | delay(50); 1140 | GetUARTdata(); 1141 | if (newData == true) { 1142 | IP1 = atoi(receivedChars); 1143 | 1144 | Serial.print("IP1: "); 1145 | Serial.println(IP1); 1146 | } 1147 | sprintf(buffer, "%d\n", SYS2 ); //Gget IP2 1148 | UARTport.print(buffer); 1149 | UARTport.flush(); 1150 | newData = false; 1151 | delay(50); 1152 | GetUARTdata(); 1153 | if (newData == true) { 1154 | IP2 = atoi(receivedChars); 1155 | 1156 | Serial.print("IP2: "); 1157 | Serial.println(IP2); 1158 | } 1159 | sprintf(buffer, "%d\n", SYS3 ); //Gget IP3 1160 | UARTport.print(buffer); 1161 | UARTport.flush(); 1162 | newData = false; 1163 | delay(50); 1164 | GetUARTdata(); 1165 | if (newData == true) { 1166 | IP3 = atoi(receivedChars); 1167 | 1168 | Serial.print("IP3: "); 1169 | Serial.println(IP3); 1170 | } 1171 | sprintf(buffer, "%d\n", SYS4 ); //Gget IP4 1172 | UARTport.print(buffer); 1173 | UARTport.flush(); 1174 | newData = false; 1175 | delay(50); 1176 | GetUARTdata(); 1177 | if (newData == true) { 1178 | IP4 = atoi(receivedChars); 1179 | 1180 | Serial.print("IP4: "); 1181 | Serial.println(IP4); 1182 | } 1183 | 1184 | sprintf(buffer, "%d\n", SYS6 ); //Gget IPGW the server gatway 1185 | UARTport.print(buffer); 1186 | UARTport.flush(); 1187 | newData = false; 1188 | delay(50); 1189 | GetUARTdata(); 1190 | if (newData == true) { 1191 | IPGW = atoi(receivedChars); 1192 | 1193 | Serial.print("IPGW: "); 1194 | Serial.println(IPGW); 1195 | } 1196 | 1197 | sprintf(buffer, "%d\n", SYS5 ); //Gget UDPport 1198 | UARTport.print(buffer); 1199 | UARTport.flush(); 1200 | newData = false; 1201 | delay(50); 1202 | GetUARTdata(); 1203 | if (newData == true) { 1204 | UDP = atoi(receivedChars); 1205 | 1206 | Serial.print("UDPport: "); 1207 | Serial.println(UDP); 1208 | } 1209 | } 1210 | 1211 | void ReadInPTpos() { //Read in the Absolute position request PT only 1212 | //Convert Pan back to Dec Degrees for input 1213 | 1214 | Serial.print("NumHex7: "); 1215 | Serial.println(NumHex7); 1216 | Serial.print("NumHex8: "); 1217 | Serial.println(NumHex8); 1218 | Serial.print("NumHex9: "); 1219 | Serial.println(NumHex9); 1220 | Serial.print("NumHex10: "); 1221 | Serial.println(NumHex10); 1222 | char buffer[30]; 1223 | sprintf(buffer, "0x%s%s%s%s", NumHex7, NumHex8, NumHex9, NumHex10); 1224 | String Hstring = (buffer); 1225 | Serial.println(Hstring); 1226 | 1227 | char H_array[7]; 1228 | Hstring.toCharArray(H_array, 7); 1229 | int x; 1230 | char *endptr; 1231 | x = strtol(H_array, &endptr, 16); 1232 | Serial.println(x, HEX); 1233 | Serial.println(x, DEC); 1234 | 1235 | if ( x >= 23090) { //If the move is negatvie 1236 | PAngleIn = (x - 23090); //Stored int16_t to provide a signed 2's value NOT REQUIRED 1237 | PAngleIn = 180 - ((PAngleIn / 235.9) ); 1238 | PAngleIn = (PAngleIn - (PAngleIn * 2)); //Sign it as negative 1239 | Serial.print("PAngleIn: "); 1240 | Serial.println(PAngleIn); 1241 | } else { 1242 | PAngleIn = x; 1243 | PAngleIn = ((PAngleIn / 117.95)); 1244 | 1245 | Serial.print("PAngleIn: "); 1246 | Serial.println(PAngleIn); 1247 | } 1248 | 1249 | 1250 | //Convert Tilt back to Dec Degrees for input 1251 | 1252 | Serial.print("NumHex11: "); 1253 | Serial.println(NumHex11); 1254 | Serial.print("NumHex12: "); 1255 | Serial.println(NumHex12); 1256 | Serial.print("NumHex13: "); 1257 | Serial.println(NumHex13); 1258 | Serial.print("NumHex14: "); 1259 | Serial.println(NumHex14); 1260 | //char buffer[30]; 1261 | sprintf(buffer, "0x%s%s%s%s", NumHex11, NumHex12, NumHex13, NumHex14); //Send the requested PT vMix position to the head 1262 | Hstring = (buffer); 1263 | Serial.println(Hstring); 1264 | 1265 | //char H_array[7]; 1266 | Hstring.toCharArray(H_array, 7); 1267 | x; 1268 | //char *endptr; 1269 | x = strtol(H_array, &endptr, 16); 1270 | Serial.println(x, HEX); 1271 | Serial.println(x, DEC); 1272 | TAngleIn = x; //Stored int16_t to provide a signed 2's value not required 1273 | if (TAngleIn > 43000) { //Then the move is negative down 1274 | TAngleIn = (x - 23090); //Stored int16_t to provide a signed 2's value 1275 | TAngleIn = 180 - ((TAngleIn / 235.9) ); 1276 | TAngleIn = (TAngleIn - (TAngleIn * 2)); //Sign it as negative 1277 | Serial.print("TAngleIn: "); 1278 | Serial.println(TAngleIn); 1279 | } else { 1280 | TAngleIn = ((TAngleIn / 235.9)); 1281 | Serial.print("TAngleIn: "); 1282 | Serial.println(TAngleIn); 1283 | } 1284 | } 1285 | void ReadInZoomFocus() { //Read in the Absolute position request PT only 1286 | //Convert Zoom back to % of Zoom 1287 | 1288 | Serial.print("NumHex4: "); 1289 | Serial.println(NumHex4); 1290 | Serial.print("NumHex5: "); 1291 | Serial.println(NumHex5); 1292 | Serial.print("NumHex6: "); 1293 | Serial.println(NumHex6); 1294 | Serial.print("NumHex7: "); 1295 | Serial.println(NumHex7); 1296 | char buffer[30]; 1297 | sprintf(buffer, "0x%s%s%s%s", NumHex4, NumHex5, NumHex6, NumHex7); //Send the vMix zoom request to the head 1298 | String Hstring = (buffer); 1299 | Serial.println(Hstring); 1300 | 1301 | char H_array[7]; 1302 | Hstring.toCharArray(H_array, 7); 1303 | int x; 1304 | char *endptr; 1305 | x = strtol(H_array, &endptr, 16); 1306 | Serial.println(x, HEX); 1307 | Serial.println(x, DEC); 1308 | 1309 | ZAngleIn = x; 1310 | ZAngleIn = ZAngleIn / 60; 1311 | 1312 | Serial.print("ZAngleIn: "); 1313 | Serial.println(ZAngleIn); 1314 | 1315 | 1316 | 1317 | //Convert Focus back to % of focus for input 1318 | 1319 | Serial.print("NumHex8: "); 1320 | Serial.println(NumHex8); 1321 | Serial.print("NumHex9: "); 1322 | Serial.println(NumHex9); 1323 | Serial.print("NumHex10: "); 1324 | Serial.println(NumHex10); 1325 | Serial.print("NumHex11: "); 1326 | Serial.println(NumHex11); 1327 | //char buffer[30]; 1328 | sprintf(buffer, "0x%s%s%s%s", NumHex8, NumHex9, NumHex10, NumHex11); //Send the focus position to the head 1329 | Hstring = (buffer); 1330 | Serial.println(Hstring); 1331 | 1332 | //char H_array[7]; 1333 | Hstring.toCharArray(H_array, 7); 1334 | x; 1335 | 1336 | x = strtol(H_array, &endptr, 16); 1337 | Serial.println(x, HEX); 1338 | Serial.println(x, DEC); 1339 | FAngleIn = x; //Stored int16_t to provide a signed 2's value not required 1340 | FAngleIn = (FAngleIn - 1000) / 604.5; //Convert bake to % of posible move 1341 | 1342 | 1343 | Serial.print("FAngleIn: "); 1344 | Serial.println(FAngleIn); 1345 | } 1346 | -------------------------------------------------------------------------------- /DB3/Update ReadMe: -------------------------------------------------------------------------------- 1 | Update v6.06 10th Jan 2024 2 | 1) Changed the way the speed is scaled from the ajustment knob on the controller when the head is being controlled using the joysticks. The knob now changes the scaller speed of the head 3 | as well as the acceloration factor allowing for very slow moves when filming or faster moves when setting up preset poses. 4 | 5 | Update v6.03 8thNov 2023 6 | 1) Fixed a bug which was causing the pan stepper to vibrate when performing very slow PTZ joystick realtime moves. 7 | 8 | Update v6.01 6thNov 2023 9 | 1) Fixed a bug which caused all PTZ WIFI cameras to adopt the same ID as the last head powered up. 10 | 11 | Update Notes v6.00: 23rd Oct 2023 12 | 13 | 1) Now supports up to 4 WIFI camera systems rather than the original 3. 14 | 2) Also know supports 9 pose/preset positions over the original 6. 16 are available for wired VISCA control 15 | 3) Two poses 15 & 16 have been reserved in order to allow triggering of the current A-B and sequencer setups with or withought bounce. 16 | these can also be triggered from VISCA by calling pose 15 or 16 respectivly. 17 | 4)The setup menu also now alows you to set a delay at the start and end of bounce moves. This also sets a recording pause at the end of A-B moves 18 | before the system returns to its home position. The pause can be 1-10 seconds. This setting is stored in memorry and recalled on reboot. 19 | 5) A number of small bugs have been fixed along the way however I am unsure which of these were in the last version and which were required as 20 | a result of the added functionality so I will not list. 21 | 6)ESP32 board updates were giving issues with the encoders this has know been fixed and we are know able to compile the code with Arduino IDE 2.* 22 | 7)The application also now uses the currently current! FastAccelStepper library. 23 | 8) Firmware numbering has been updated across the hole system. To keep things simple all parts of the system must be running the first part of the version number so this update is 6. 24 | If indevidual parts of the system require an update which does not effect the other parts this can happen as here v6.03. The first number "6" will only increment if the update effect all parts of the system 25 | and it will increment on all firmware parts. So in the case of this update all parts of the system must be updated to v6.** stay compatable. 26 | -------------------------------------------------------------------------------- /DB_PanTilt_Balanced/ReadMe: -------------------------------------------------------------------------------- 1 | # Software Updates: 2 | Update Note v6.03 Beta - This Beta version has not been fully tested but changes the way the system workswith the PTZplus joystick bringing it intoline with the code written for the DB3 head 3 | users should also see the acceloration knob on the PTZplus control have a greater impact on move speed and control. 4 | Update Notes v6.01: 6th Nov 2023 5 | 1. Fixes a bug which caused all WIFI PTZ heads to adopt the same ID as the last head turned on. 6 | 2. Added a way for Focus, Zoom, and Tilt limits function to be triggered from VISCA using preset 100. Preset 100 needs to be triggered three times to 7 | complete the function. 8 | 3. Fixed a bug where Limit set was triggered on all cameras not just the current live camera as intended. 9 | 10 | Update Notes v6.00: 23rd Oct 2023 11 | 12 | 1) Now supports up to 4 WIFI camera systems rather than the original 3. 13 | 2) Also know supports 9 pose/preset positions over the original 6. 16 are available for wired VISCA control 14 | 3) Two poses 15 & 16 have been reserved in order to allow triggering of the current A-B and sequencer setups with or withought bounce. 15 | these can also be triggered from VISCA by calling pose 15 or 16 respectivly. 16 | 4)The setup menu also now alows you to set a delay at the start and end of bounce moves. This also sets a recording pause at the end of A-B moves 17 | before the system returns to its home position. The pause can be 1-10 seconds. This setting is stored in memorry and recalled on reboot. 18 | 5) A number of small bugs have been fixed along the way however I am unsure which of these were in the last version and which were required as 19 | a result of the added functionality so I will not list. 20 | 6)ESP32 board updates were giving issues with the encoders this has know been fixed and we are know able to compile the code with Arduino IDE 2.* 21 | 7)The application also now uses the currently current! FastAccelStepper library. 22 | 8) Firmware numbering has been updated across the hole system. To keep things simple all parts of the system must be running the first part of the version number so this update is 6. 23 | If indevidual parts of the system require an update which does not effect the other parts this can happen as here v6.02. The first number "6" will only increment if the update effect all parts of the system 24 | and it will increment on all firmware parts. So in the case of this update all parts of the system must be updated to v6.** stay compatable. 25 | -------------------------------------------------------------------------------- /DB_PanTilt_OT/ReadMe: -------------------------------------------------------------------------------- 1 | # Software Updates: 2 | 3 | Update Notes v6.03: March 2025 4 | 1) Updated speed control from PTZplus controler in line with other PTZ heads 5 | Update Notes v6.01: 6th Nov 2023 6 | 1. Fixes a bug which caused all WIFI PTZ heads to adopt the same ID as the last head turned on. 7 | 2. Added a way for Focus, Zoom, and Tilt limits function to be triggered from VISCA using preset 100. Preset 100 needs to be triggered three times to 8 | complete the function. 9 | 3. Fixed a bug where Limit set was triggered on all cameras not just the current live camera as intended. 10 | 11 | Update Notes v6.00: 23rd Oct 2023 12 | 13 | 1) Now supports up to 4 WIFI camera systems rather than the original 3. 14 | 2) Also know supports 9 pose/preset positions over the original 6. 16 are available for wired VISCA control 15 | 3) Two poses 15 & 16 have been reserved in order to allow triggering of the current A-B and sequencer setups with or withought bounce. 16 | these can also be triggered from VISCA by calling pose 15 or 16 respectivly. 17 | 4)The setup menu also now alows you to set a delay at the start and end of bounce moves. This also sets a recording pause at the end of A-B moves 18 | before the system returns to its home position. The pause can be 1-10 seconds. This setting is stored in memorry and recalled on reboot. 19 | 5) A number of small bugs have been fixed along the way however I am unsure which of these were in the last version and which were required as 20 | a result of the added functionality so I will not list. 21 | 6)ESP32 board updates were giving issues with the encoders this has know been fixed and we are know able to compile the code with Arduino IDE 2.* 22 | 7)The application also now uses the currently current! FastAccelStepper library. 23 | 8) Firmware numbering has been updated across the hole system. To keep things simple all parts of the system must be running the first part of the version number so this update is 6. 24 | If indevidual parts of the system require an update which does not effect the other parts this can happen as here v6.02. The first number "6" will only increment if the update effect all parts of the system 25 | and it will increment on all firmware parts. So in the case of this update all parts of the system must be updated to v6.** stay compatable. 26 | -------------------------------------------------------------------------------- /Digital Bird PTZplus WIFI Control Quickstart V6.03.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Digital Bird PTZplus WIFI Control Quickstart V6.03.pdf -------------------------------------------------------------------------------- /DigitalBird-Software Installation Guide .pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/DigitalBird-Software Installation Guide .pdf -------------------------------------------------------------------------------- /ESP32 Dev Board form factor.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/ESP32 Dev Board form factor.jpeg -------------------------------------------------------------------------------- /Easy_Nextion_Library-DB.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/Easy_Nextion_Library-DB.zip -------------------------------------------------------------------------------- /FastAccelStepper-master_DB.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/FastAccelStepper-master_DB.zip -------------------------------------------------------------------------------- /FastLED-master.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/FastLED-master.zip -------------------------------------------------------------------------------- /GOC/DB3_VISCA_Decoder_1.01.ino: -------------------------------------------------------------------------------- 1 | /* 2 | 3 | Digital Bird Visca Decoder- POE ethernet UDP to UART export v1.0 Sept 2023 4 | change Log: 5 | 1) Preset speed added to viscacommand set allowing you to modify the speed of preset moves 6 | 2) Bug Fix where IP was not always being received correctly from the upper head CPU at startup 7 | */ 8 | 9 | #define DEBUG_ETHERNET_WEBSERVER_PORT Serial 10 | // Debug Level from 0 to 4 11 | #define _ETHERNET_WEBSERVER_LOGLEVEL_ 3 12 | #include 13 | #include 14 | HardwareSerial UARTport(2); // use UART2 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include "sntp.h" 20 | 21 | 22 | // Select the IP address according to your local network 23 | IPAddress myIP(192, 168, 137, 80); 24 | IPAddress myGW(192, 168, 137, 1); 25 | IPAddress mySN(255, 255, 255, 0); 26 | IPAddress myDNS(192, 168, 137, 1); //Adress to send out on 27 | 28 | char timeServer[] = "time.nist.gov"; // NTP server 29 | unsigned int localPort = 1259; // local port to listen for UDP packets 30 | 31 | const int NTP_PACKET_SIZE = 48; // NTP timestamp is in the first 48 bytes of the message 32 | const int UDP_TIMEOUT = 10; // timeout in miliseconds to wait for an UDP packet to arrive 33 | 34 | byte packetBuffer[NTP_PACKET_SIZE]; // buffer to hold incoming and outgoing packets 35 | 36 | // A UDP instance to let us send and receive packets over UDP 37 | WiFiUDP Udp; 38 | 39 | // send an NTP request to the time server at the given address 40 | 41 | 42 | //Example return codes 43 | byte acknowledge[3] = {0x90, 0x41, 0xFF}; // Return for accept command 44 | byte acceptC[3] = {0x90, 0x38, 0xFF}; // Return for accept command 45 | 46 | //Required for inital camera setup 47 | byte PTposition[12] = {0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF}; //Pan Tilt current position reply 11 48 | byte ZoomPosition[7] = {0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0xFF}; //Zoom position reply = Zoom x1 49 | byte FocusPosition[7] = {0x90, 0x50, 0x00, 0x00, 0x00, 0x00, 0xFF}; //Focus position reply = infinity 50 | byte Confirm[3] = {0x90, 0x42, 0xFF}; //Accept comands return 51 | byte complete[3] = {0x90, 0x51, 0xFF}; // Return code for Command Complete 52 | 53 | const byte numChars = 4; //For uart reception 54 | char receivedChars[numChars]; // An array to store the received data from UART 55 | 56 | boolean newData = false; 57 | int Tally; 58 | int Pose; 59 | long TAngle; 60 | long ZAngle; 61 | long FAngle; 62 | long PAngle; 63 | char P1[2]; 64 | char P2[2]; 65 | char P3[2]; 66 | char P4[2]; 67 | char P5[2]; 68 | char P6[2]; 69 | char P7[2]; 70 | char P8[2]; 71 | char P9[2]; 72 | int ViscaPacketSize; 73 | int ViscaMove; 74 | int ViscaPanSpeed; 75 | int ViscaTiltSpeed; 76 | int ViscaFocusSpeed; 77 | int ViscaZoomSpeed; 78 | int Speed; //Generic holder for speed 79 | int PanSpeed; 80 | int TiltSpeed; 81 | int FocusSpeed; 82 | int ZoomSpeed; 83 | int PoseNumber; 84 | int PoseSpeed; 85 | const byte bufferSize = 11; 86 | char serialBuffer[bufferSize]; 87 | byte bufferIndex = 0; 88 | char EOL = '\n'; 89 | bool hasData = false; 90 | 91 | int IP1 = 0; 92 | int IP2 = 0; 93 | int IP3 = 0; 94 | int IP4 = 0; 95 | int IPGW = 0; 96 | int UDP = 0; 97 | int ViscaComand; 98 | int stopcheck; // For checking when a STOP command is received (0) 99 | int checksum; // For Calculating Checksum. Sum of the payload bytes (bytes 1 through 8) in the message 100 | int ByteNumber; // Counter for reading the serial buffer 101 | const char * returnIP; 102 | int returnPort; 103 | byte byteReceived[9]; 104 | int request = 0; 105 | char *payloadString; 106 | unsigned long entry; 107 | int IPCheck; 108 | 109 | String NumHex4; 110 | String NumHex5; 111 | String NumHex6; 112 | String NumHex7; 113 | String NumHex8; 114 | String NumHex9; 115 | String NumHex10; 116 | String NumHex11; 117 | String NumHex12; 118 | String NumHex13; 119 | String NumHex14; 120 | 121 | int PAngleIn; 122 | int TAngleIn; 123 | int ZAngleIn; 124 | int FAngleIn; 125 | void setup() { 126 | 127 | 128 | 129 | 130 | Serial.begin(115200); 131 | UARTport.begin(9600, SERIAL_8N1, 14, 15); 132 | 133 | while (IP1 != 192) { 134 | GetIP(); 135 | } 136 | // Select the IP address according to your local network 137 | IPAddress myIP(IP1, IP2, IP3, IP4); 138 | IPAddress myGW(IP1, IP2, IP3, IPGW); 139 | IPAddress myDNS(IP1, IP2, IP3, IPGW); 140 | IPAddress mySN(255, 255, 255, 0); 141 | Serial.print("\nIP address found from head set to " + String(IP1)); 142 | Serial.print("\nIP address found from head set to " + String(IP2)); 143 | Serial.print("\nIP address found from head set to " + String(IP3)); 144 | Serial.print("\nIP address found from head set to " + String(IP4)); 145 | while (!Serial); 146 | 147 | 148 | Serial.print("\nStarting UdpNTPClient on " + String(ARDUINO_BOARD)); 149 | Serial.println(" with " + String(SHIELD_TYPE)); 150 | Serial.println(WEBSERVER_WT32_ETH01_VERSION); 151 | 152 | 153 | WT32_ETH01_onEvent(); // To be called before ETH.begin() 154 | ETH.begin(ETH_PHY_ADDR, ETH_PHY_POWER); 155 | ETH.config(myIP, myGW, mySN, myDNS); 156 | WT32_ETH01_waitForConnect(); 157 | Udp.begin(localPort); 158 | 159 | 160 | 161 | 162 | } 163 | 164 | void loop() { 165 | //if (IPCheck==0){ 166 | // listenForUART(); 167 | //} 168 | 169 | // wait for a reply for UDP_TIMEOUT miliseconds 170 | unsigned long startMs = millis(); 171 | while (!Udp.available() && (millis() - startMs) < UDP_TIMEOUT) {} 172 | 173 | 174 | 175 | 176 | int packetSize = Udp.parsePacket(); // if there's data available, read a packet 177 | if (packetSize) { 178 | 179 | Udp.read(packetBuffer, NTP_PACKET_SIZE); 180 | Serial.println(); 181 | ViscaPacketSize = packetSize; 182 | 183 | 184 | Serial.print(", Last Paket count: "); 185 | Serial.println (ViscaPacketSize); 186 | Serial.print(packetBuffer[0]); 187 | Serial.print(", "); 188 | Serial.print(packetBuffer[1]); 189 | Serial.print(", "); 190 | Serial.print(packetBuffer[2]); 191 | Serial.print(", "); 192 | Serial.print(packetBuffer[3]); 193 | Serial.print(", "); 194 | Serial.print(packetBuffer[4]); 195 | Serial.print(", "); 196 | Serial.print(packetBuffer[5]); 197 | Serial.print(", "); 198 | Serial.print(packetBuffer[6]); 199 | Serial.print(", "); 200 | Serial.print(packetBuffer[7]); 201 | Serial.print(", "); 202 | Serial.print(packetBuffer[8]); 203 | Serial.println(""); 204 | Serial.print (packetBuffer[9]); 205 | Serial.print(", "); 206 | Serial.print(packetBuffer[10]); 207 | Serial.print(", "); 208 | Serial.print(packetBuffer[11]); 209 | Serial.print(", "); 210 | Serial.print(packetBuffer[12]); 211 | Serial.print(", "); 212 | Serial.print(packetBuffer[13]); 213 | Serial.print(", "); 214 | Serial.print(packetBuffer[14]); 215 | Serial.print(", "); 216 | Serial.print(packetBuffer[15]); 217 | Serial.print(", "); 218 | Serial.print(packetBuffer[16]); 219 | Serial.print(", "); 220 | Serial.print(packetBuffer[17]); 221 | Serial.println(""); 222 | 223 | 224 | 225 | 226 | //*********************Establish a DB move code fron the two packets before FF using Decimal Values******************** 227 | if (ViscaPacketSize == 5) { 228 | 229 | ViscaComand = packetBuffer[2] * 10 + (packetBuffer[3]); 230 | } 231 | if (ViscaPacketSize == 6) { 232 | ViscaComand = (packetBuffer[3] * 100 + (packetBuffer[4])); 233 | if ((packetBuffer[1] + packetBuffer[2] + packetBuffer[3]) == 14) { 234 | ViscaComand = 14; 235 | Tally = packetBuffer[4]; 236 | } 237 | if ((packetBuffer[1] + packetBuffer[2] + packetBuffer[3]) == 8) { 238 | ViscaComand = 137; 239 | PoseSpeed = packetBuffer[4]; 240 | } 241 | 242 | } 243 | 244 | if (ViscaPacketSize == 7) { 245 | if (ViscaComand = (packetBuffer[2] == 4)) { 246 | ViscaComand = (packetBuffer[2] * 10 + (packetBuffer[4])); 247 | PoseNumber = (packetBuffer[5]); 248 | } else { 249 | ViscaComand = packetBuffer[2]; 250 | }; 251 | if (ViscaComand == 40 || ViscaComand == 41 || ViscaComand == 42) { //If Command is a pose find out the pose requested 252 | Pose = (packetBuffer[5]); 253 | } 254 | 255 | } 256 | if (ViscaPacketSize == 8) { 257 | ViscaComand = (packetBuffer[2] * 10 + packetBuffer[4]); 258 | } 259 | if (ViscaPacketSize == 9) { 260 | ViscaComand = (packetBuffer[6] * 10 + packetBuffer[7]); 261 | PanSpeed = ((packetBuffer[4])); 262 | TiltSpeed = ((packetBuffer[5])); 263 | if (packetBuffer[3] == 71) { 264 | ViscaComand = 71; 265 | } 266 | } 267 | 268 | //For OBS padded commands 269 | if (ViscaPacketSize == 13) { 270 | ViscaComand = (packetBuffer[10] * 10 + packetBuffer[11]); // All 13 comands except the absolute position commands 271 | if (packetBuffer[1] + packetBuffer[2] + packetBuffer[3] == 76) { //Then Abolute zoom/Focus move requested eg vMix position 272 | ViscaComand = 76; 273 | NumHex4 = String(packetBuffer[4], HEX); 274 | NumHex5 = String(packetBuffer[5], HEX); 275 | NumHex6 = String(packetBuffer[6], HEX); 276 | NumHex7 = String(packetBuffer[7], HEX); 277 | NumHex8 = String(packetBuffer[8], HEX); 278 | NumHex9 = String(packetBuffer[9], HEX); 279 | NumHex10 = String(packetBuffer[10], HEX); 280 | NumHex11 = String(packetBuffer[11], HEX); 281 | } 282 | if (packetBuffer[1] + packetBuffer[2] + packetBuffer[3] == 77) { //Then Abolute Focus move requested eg vMix position 283 | ViscaComand = 77; 284 | } 285 | } 286 | if (ViscaPacketSize == 14) { 287 | ViscaComand = (packetBuffer[11] * 100 + packetBuffer[12]); 288 | 289 | } 290 | if (ViscaPacketSize == 15) { 291 | if (ViscaComand = (packetBuffer[10] == 4)) { 292 | ViscaComand = (packetBuffer[10] * 10 + packetBuffer[12]); 293 | PoseNumber = (packetBuffer[13]); 294 | } else { 295 | ViscaComand = packetBuffer[10]; 296 | } 297 | if (ViscaComand == 40 || 41 || 42) { //If Command is a pose find out the pose requested 298 | Pose = (packetBuffer[13]); 299 | } 300 | if (packetBuffer[1] + packetBuffer[2] + packetBuffer[3] == 9) { //Then Abolute move requested eg vMix position 301 | ViscaComand = 9; 302 | PanSpeed = packetBuffer[6]; 303 | TiltSpeed = packetBuffer[5]; 304 | NumHex7 = String(packetBuffer[7], HEX); 305 | NumHex8 = String(packetBuffer[8], HEX); 306 | NumHex9 = String(packetBuffer[9], HEX); 307 | NumHex10 = String(packetBuffer[10], HEX); 308 | NumHex11 = String(packetBuffer[11], HEX); 309 | NumHex12 = String(packetBuffer[12], HEX); 310 | NumHex13 = String(packetBuffer[13], HEX); 311 | NumHex14 = String(packetBuffer[14], HEX); 312 | } 313 | 314 | } 315 | 316 | 317 | if (ViscaPacketSize == 16) { 318 | ViscaComand = (packetBuffer[10] * 10 + packetBuffer[12]); 319 | } 320 | if (ViscaPacketSize == 17) { 321 | ViscaComand = (packetBuffer[14] * 10) + packetBuffer[15]; 322 | PanSpeed = ((packetBuffer[12])); 323 | TiltSpeed = ((packetBuffer[13])); 324 | } 325 | 326 | 327 | for ( int i = 0; i < ViscaPacketSize; ++i ) { //Clear the buffer 328 | packetBuffer[i] = (char)0; 329 | 330 | 331 | } 332 | 333 | 334 | 335 | //*******************Visca comands******************* 336 | 337 | //Udp.beginPacket(myGW, 1259); 338 | //Visca Returns requested at setup 339 | // if (ViscaComand == 78) { //Pant Tilt position request 340 | // Udp.write(PTposition, 11); 341 | // Serial.println ("PT position requested"); 342 | // delay(200); 343 | // } 344 | if (ViscaComand == 111) { //Zoom Position request 345 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 346 | Udp.write(ZoomPosition, 7); 347 | Udp.endPacket(); 348 | Serial.println ("Zoom position requested"); 349 | 350 | //delay(200); 351 | } 352 | if (ViscaComand == 112) { //Focus position request 353 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 354 | Udp.write(FocusPosition, 7); 355 | Udp.endPacket(); 356 | Serial.println ("Focus position requested"); 357 | //delay(200); 358 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 359 | Udp.write(Confirm, 3); 360 | Udp.endPacket(); 361 | Serial.println ("Confirm sent"); 362 | } 363 | 364 | 365 | 366 | 367 | 368 | } 369 | char buffer[50]; 370 | switch (ViscaComand) { 371 | 372 | case 3802: Serial.println ("AKA"); 373 | Udp.beginPacket(myGW, UDP); 374 | Udp.write(Confirm, 3); 375 | Udp.endPacket(); 376 | Serial.println ("Confirm sent"); 377 | break; 378 | 379 | case 14: Serial.println ("Tally light command:"); 380 | sprintf(buffer, "%d,%d\n", ViscaComand, Tally); 381 | UARTport.print(buffer); 382 | Serial.print (Tally); break; 383 | 384 | case 76: Serial.println ("Zoom/Focus Absolute position move request"); 385 | ReadInZoomFocus(); 386 | Serial.print("PanSpeed: "); 387 | Serial.println(PanSpeed); 388 | Serial.print("TiltSpeed: "); 389 | Serial.println(TiltSpeed); 390 | Serial.print("PAngleIn: "); 391 | Serial.println(PAngleIn); 392 | Serial.print("TAngleIn: "); 393 | Serial.println(TAngleIn); 394 | Serial.print("FAngleIn: "); 395 | Serial.println(FAngleIn); 396 | Serial.print("ZAngleIn: "); 397 | Serial.println(ZAngleIn); 398 | Serial.println("Sending vMix Absolute position request to PTZ head"); 399 | ViscaComand = 9; 400 | sprintf(buffer, "%d,%d,%d,%d,%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed, PAngleIn, TAngleIn, FAngleIn, ZAngleIn ); 401 | UARTport.print(buffer); 402 | break; 403 | 404 | case 77: Serial.println ("Focus Absolute position move request"); 405 | //Read in the Focus request here 406 | Udp.beginPacket(myGW, 1259); 407 | Udp.write(Confirm, 3); 408 | Udp.endPacket(); 409 | Serial.println ("Confirm sent"); 410 | break; 411 | 412 | case 9: Serial.println ("PT Absolute position move request from vMix"); 413 | ReadInPTpos(); 414 | sprintf(buffer, "%d,%d,%d,%d,%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed, PAngleIn, TAngleIn, FAngleIn, ZAngleIn ); 415 | UARTport.print(buffer); break; 416 | break; 417 | 418 | case 5603: Serial.println("Manual focus"); 419 | Udp.beginPacket(myGW, 1259); 420 | Udp.write(Confirm, 3); 421 | Udp.endPacket(); 422 | Serial.println ("Confirm sent"); 423 | break; 424 | 425 | case 71: ("Send focus home"); 426 | Udp.beginPacket(myGW, 1259); 427 | Udp.write(Confirm, 3); 428 | Udp.endPacket(); break; 429 | 430 | case 78: Serial.println ("PT position requested1"); 431 | sprintf(buffer, "%d\n", ViscaComand ); 432 | UARTport.print(buffer); //Send request to PTZ head 433 | int Request; 434 | if (Request = 0) { 435 | Serial.println ("CHECKING FOR UART reply"); 436 | listenForUART(); 437 | Serial.print("PAngle: "); 438 | Serial.println(PAngle); 439 | Serial.print("TAngle: "); 440 | Serial.println(TAngle); 441 | Serial.print("ZAngle: "); 442 | Serial.println(ZAngle); 443 | Serial.print("FAngle: "); 444 | Serial.println(FAngle); 445 | Serial.println(PTposition[0]); 446 | Serial.println(PTposition[1]); 447 | Serial.println(PTposition[10]); 448 | 449 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 450 | Udp.write(PTposition, 11); 451 | Udp.endPacket(); 452 | //delay(200); 453 | Request = 2; 454 | } else { 455 | //PTposition[2] = 0x00; PTposition[3] = 0x05; PTposition[4] = 0x02; PTposition[5] = 0x0E; PTposition[6] = 0x0F; break; 456 | Udp.beginPacket(Udp.remoteIP(), Udp.remotePort()); 457 | Udp.write(PTposition, 11); 458 | Udp.endPacket(); 459 | //delay(200); 460 | Request = 0; 461 | Serial.println(PTposition[0] ); 462 | Serial.println(PTposition[1]); 463 | Serial.println(PTposition[2]); 464 | Serial.println(PTposition[3]); 465 | Serial.println(PTposition[4]); 466 | Serial.println(PTposition[5]); 467 | Serial.println(PTposition[6]); 468 | Serial.println(PTposition[7]); 469 | Serial.println(PTposition[8]); 470 | Serial.println(PTposition[9]); 471 | Serial.println(PTposition[10]); 472 | Serial.println(PTposition[11]); 473 | } 474 | break; 475 | 476 | 477 | 478 | 479 | case 64: Serial.print(", PT Home "); 480 | sprintf(buffer, "%d\n", ViscaComand ); 481 | UARTport.print(buffer); break; 482 | 483 | 484 | 485 | 486 | case 33: Serial.print(", PT Stop "); 487 | sprintf(buffer, "%d\n", ViscaComand ); 488 | UARTport.print(buffer); 489 | delay(20); 490 | listenForUART(); 491 | Serial.print("IP4 "); 492 | Serial.print(IP4); 493 | break; 494 | 495 | case 700: Serial.print(", Zoom Stop "); 496 | sprintf(buffer, "%d\n", ViscaComand ); 497 | UARTport.print(buffer); 498 | delay(20); 499 | listenForUART(); 500 | break; 501 | 502 | case 800: Serial.print(", Focus Stop 1 "); 503 | Serial.print(ViscaComand); 504 | sprintf(buffer, "%d\n", ViscaComand ); 505 | UARTport.print(buffer); 506 | delay(20); 507 | listenForUART(); 508 | break; 509 | case 13: Serial.print(", Pan Left "); 510 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 511 | UARTport.print(buffer); break; 512 | 513 | 514 | case 23: Serial.print(", Pan Right "); 515 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 516 | UARTport.print(buffer); break; 517 | 518 | case 31: Serial.print(", Tilt Up "); 519 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 520 | UARTport.print(buffer); break; 521 | 522 | case 32: Serial.print(", Tilt Down "); 523 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 524 | UARTport.print(buffer); break; 525 | 526 | case 11: Serial.print(", Up Left "); 527 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 528 | UARTport.print(buffer); break; 529 | 530 | case 21: Serial.print(", Up Right "); 531 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 532 | UARTport.print(buffer); break; 533 | 534 | case 12: Serial.print(", Down Left "); 535 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 536 | UARTport.print(buffer); break; 537 | 538 | case 22: Serial.print(", Down Right "); 539 | sprintf(buffer, "%d,%d,%d\n", ViscaComand, PanSpeed, TiltSpeed ); 540 | UARTport.print(buffer); break; 541 | 542 | case 748: Serial.print(", Zoom out p1 "); 543 | sprintf(buffer, "%d\n", ViscaComand ); 544 | UARTport.print(buffer); break; 545 | 546 | case 749: Serial.print(", Zoom out p2 "); 547 | sprintf(buffer, "%d\n", ViscaComand ); 548 | UARTport.print(buffer); break; 549 | 550 | case 750: Serial.print(", Zoom out p3 "); 551 | sprintf(buffer, "%d\n", ViscaComand ); 552 | UARTport.print(buffer); break; 553 | 554 | case 751: Serial.print(", Zoom out p4 "); 555 | sprintf(buffer, "%d\n", ViscaComand ); 556 | UARTport.print(buffer); break; 557 | 558 | case 752: Serial.print(", Zoom out p5 "); 559 | sprintf(buffer, "%d\n", ViscaComand ); 560 | UARTport.print(buffer); break; 561 | 562 | case 753: Serial.print(", Zoom out p6 "); 563 | sprintf(buffer, "%d\n", ViscaComand ); 564 | UARTport.print(buffer); break; 565 | 566 | case 754: Serial.print(", Zoom out p7 "); 567 | sprintf(buffer, "%d\n", ViscaComand ); 568 | UARTport.print(buffer); break; 569 | 570 | case 755: Serial.print(", Zoom out p8 "); 571 | sprintf(buffer, "%d\n", ViscaComand ); 572 | UARTport.print(buffer); break; 573 | 574 | case 756: Serial.print(", Zoom out p9 "); 575 | sprintf(buffer, "%d\n", ViscaComand ); 576 | UARTport.print(buffer); break; 577 | 578 | case 732: Serial.print(", Zoom in p1 "); 579 | sprintf(buffer, "%d\n", ViscaComand ); 580 | UARTport.print(buffer); break; 581 | 582 | case 733: Serial.print(", Zoom in p2 "); 583 | sprintf(buffer, "%d\n", ViscaComand ); 584 | UARTport.print(buffer); break; 585 | 586 | case 734: Serial.print(", Zoom in p3 "); 587 | sprintf(buffer, "%d\n", ViscaComand ); 588 | UARTport.print(buffer); break; 589 | 590 | case 735: Serial.print(", Zoom in p4 "); 591 | sprintf(buffer, "%d\n", ViscaComand ); 592 | UARTport.print(buffer); break; 593 | 594 | case 736: Serial.print(", Zoom in p5 "); 595 | sprintf(buffer, "%d\n", ViscaComand ); 596 | UARTport.print(buffer); break; 597 | 598 | case 737: Serial.print(", Zoom in p6 "); 599 | sprintf(buffer, "%d\n", ViscaComand ); 600 | UARTport.print(buffer); break; 601 | 602 | case 738: Serial.print(", Zoom in p7 "); 603 | sprintf(buffer, "%d\n", ViscaComand ); 604 | UARTport.print(buffer); break; 605 | 606 | case 739: Serial.print(", Zoom in p8 "); 607 | sprintf(buffer, "%d\n", ViscaComand ); 608 | UARTport.print(buffer); break; 609 | 610 | case 2402: Serial.print(", Focus Stop "); 611 | Serial.print(ViscaComand); 612 | sprintf(buffer, "%d\n", ViscaComand ); 613 | UARTport.print(buffer); 614 | delay(20); 615 | listenForUART(); 616 | break; 617 | case 832: Serial.print(", Focus Near p1 "); 618 | sprintf(buffer, "%d\n", ViscaComand ); 619 | UARTport.print(buffer); break; 620 | 621 | case 833: Serial.print(", Focus Near p2 "); 622 | sprintf(buffer, "%d\n", ViscaComand ); 623 | UARTport.print(buffer); break; 624 | 625 | case 834: Serial.print(", Focus Near p3 "); 626 | sprintf(buffer, "%d\n", ViscaComand ); 627 | UARTport.print(buffer); break; 628 | 629 | case 835: Serial.print(", Focus Near p4 "); 630 | sprintf(buffer, "%d\n", ViscaComand ); 631 | UARTport.print(buffer); break; 632 | 633 | case 836: Serial.print(", Focus Near p5 "); 634 | sprintf(buffer, "%d\n", ViscaComand ); 635 | UARTport.print(buffer); break; 636 | 637 | case 837: Serial.print(", Focus Near p6 "); 638 | sprintf(buffer, "%d\n", ViscaComand ); 639 | UARTport.print(buffer); break; 640 | 641 | case 838: Serial.print(", Focus Near p7 "); 642 | sprintf(buffer, "%d\n", ViscaComand ); 643 | UARTport.print(buffer); break; 644 | 645 | case 839: Serial.print(", Focus Near p8 "); 646 | sprintf(buffer, "%d\n", ViscaComand ); 647 | UARTport.print(buffer); break; 648 | 649 | case 848: Serial.print(", Focus Far p1 "); 650 | sprintf(buffer, "%d\n", ViscaComand ); 651 | UARTport.print(buffer); break; 652 | 653 | case 849: Serial.print(", Focus Far p2 "); 654 | sprintf(buffer, "%d\n", ViscaComand ); 655 | UARTport.print(buffer); break; 656 | 657 | case 850: Serial.print(", Focus Far p3 "); 658 | sprintf(buffer, "%d\n", ViscaComand ); 659 | UARTport.print(buffer); break; 660 | 661 | case 851: Serial.print(", Focus Far p4 "); 662 | sprintf(buffer, "%d\n", ViscaComand ); 663 | UARTport.print(buffer); break; 664 | 665 | case 852: Serial.print(", Focus Far p5 "); 666 | sprintf(buffer, "%d\n", ViscaComand ); 667 | UARTport.print(buffer); break; 668 | 669 | case 853: Serial.print(", Focus Far p6 "); 670 | sprintf(buffer, "%d\n", ViscaComand ); 671 | UARTport.print(buffer); break; 672 | 673 | case 854: Serial.print(", Focus Far p7 "); 674 | sprintf(buffer, "%d\n", ViscaComand ); 675 | UARTport.print(buffer); break; 676 | 677 | case 855: Serial.print(", Focus Far p8 "); 678 | sprintf(buffer, "%d\n", ViscaComand ); 679 | UARTport.print(buffer); break; 680 | 681 | case 4901: Serial.print(", Ramp/EaseValue=1 "); 682 | sprintf(buffer, "%d\n", ViscaComand ); 683 | UARTport.print(buffer); break; 684 | 685 | case 4902: Serial.print(", Ramp/EaseValue=2 "); 686 | sprintf(buffer, "%d\n", ViscaComand ); 687 | UARTport.print(buffer); break; 688 | 689 | case 4903: Serial.print(", Ramp/EaseValue=3 "); 690 | sprintf(buffer, "%d\n", ViscaComand ); 691 | UARTport.print(buffer); break; 692 | 693 | case 2: Serial.print(", Start Recore "); 694 | sprintf(buffer, "%d\n", ViscaComand ); 695 | UARTport.print(buffer); break; 696 | 697 | case 3: Serial.print(", Stop Record "); 698 | sprintf(buffer, "%d\n", ViscaComand ); 699 | UARTport.print(buffer); break; 700 | 701 | case 41: Serial.print(", Save Pose "); 702 | Serial.print(Pose); 703 | sprintf(buffer, "%d,%d\n", ViscaComand, Pose ); 704 | UARTport.print(buffer); break; 705 | 706 | case 42: Serial.print(", Move to pose "); 707 | Serial.print(Pose); 708 | sprintf(buffer, "%d,%d\n", ViscaComand, Pose ); 709 | UARTport.print(buffer); break; 710 | 711 | case 40: Serial.print(", Reset Pose do Defaults "); 712 | Serial.print(Pose); 713 | sprintf(buffer, "%d,%d\n", ViscaComand, Pose ); 714 | UARTport.print(buffer); break; 715 | 716 | 717 | case 126: Serial.print(", Record Mode setting "); 718 | sprintf(buffer, "%d\n", ViscaComand ); 719 | UARTport.print(buffer); break; 720 | 721 | case 137: Serial.print(", Pose speed "); 722 | sprintf(buffer, "%d,%d\n", ViscaComand,PoseSpeed ); 723 | UARTport.print(buffer); break; 724 | 725 | 726 | 727 | 728 | } 729 | ViscaComand = 0; //Clear the Comand ready to start fresh 730 | } 731 | void listenForUART() { 732 | //Serial.println ("Listening"); 733 | char buffer[30]; 734 | int PP = 78; 735 | int TT = 79; 736 | int ZZ = 80; 737 | int FF = 81; 738 | int SYS1 = 665; 739 | int SYS2 = 666; 740 | int SYS3 = 667; 741 | int SYS4 = 668; 742 | int SYS5 = 669; 743 | 744 | static byte ndx = 0; 745 | char endMarker = '\n'; 746 | char rc; 747 | 748 | sprintf(buffer, "%d\n", PP );//First Pass get PP 749 | UARTport.print(buffer); 750 | UARTport.flush(); 751 | newData = false; 752 | delay(50); 753 | GetUARTdata(); 754 | if (newData == true) { 755 | PAngle = atoi(receivedChars); 756 | PAngle = PAngle * 2; 757 | //PAngle = 10 * ((PAngle + 5) / 10); //Round to nearest 10 758 | 759 | // if (PAngle < 0) { 760 | // PAngle = abs(PAngle) + 1000; 761 | // } 762 | Serial.print("\n"); 763 | Serial.print("PAngle: "); 764 | Serial.println(PAngle); 765 | if (PAngle < 0) { 766 | Serial.print("PAngle is negative "); 767 | } else { 768 | Serial.print("PAngle is Posative "); 769 | } 770 | } 771 | 772 | sprintf(buffer, "%d\n", TT ); //Second pass get TT 773 | delay(100); 774 | UARTport.print(buffer); 775 | UARTport.flush(); 776 | newData = false; 777 | delay(50); 778 | GetUARTdata(); 779 | if (newData == true) { 780 | TAngle = atoi(receivedChars) * 2; 781 | //TAngle = 10 * ((TAngle + 5) / 10); //Round to nearest 10 782 | // if (TAngle < 0) { 783 | // TAngle = abs(TAngle) + 1000; 784 | // } 785 | Serial.print("TAngle: "); 786 | Serial.println(TAngle); 787 | } 788 | 789 | sprintf(buffer, "%d\n", FF ); //Third pass get FF 790 | delay(100); 791 | UARTport.print(buffer); 792 | UARTport.flush(); 793 | newData = false; 794 | delay(50); 795 | GetUARTdata(); 796 | if (newData == true) { 797 | FAngle = atoi(receivedChars); 798 | FAngle = abs(FAngle); 799 | Serial.print("FAngle=: "); //This gets past back to VISCA position save 800 | Serial.println(FAngle); 801 | } 802 | 803 | sprintf(buffer, "%d\n", ZZ ); //Forth pass get ZZ 804 | delay(100); 805 | UARTport.print(buffer); 806 | UARTport.flush(); 807 | newData = false; 808 | delay(50); 809 | GetUARTdata(); 810 | if (newData == true) { 811 | ZAngle = atoi(receivedChars); 812 | ZAngle = abs(ZAngle); 813 | Serial.print("ZAngle: "); 814 | Serial.println(ZAngle); 815 | } 816 | //Convert to uint8 for output 817 | 818 | 819 | if (PAngle > 0) { 820 | PAngle = PAngle * 117.95; //divisions reduced from norm to make establisheing sign of value easier 821 | } else { 822 | PAngle = PAngle * 235.9; 823 | } 824 | 825 | TAngle = TAngle * 235.9; 826 | 827 | Serial.print("PAngle: "); 828 | Serial.println(PAngle); 829 | if (PAngle < 0) { 830 | Serial.print("PAngle is negative "); 831 | } else { 832 | Serial.print("PAngle is Posative "); 833 | } 834 | if (PAngle < 0) { //If Pangle negative 835 | PTposition[2] = {0x0F}; 836 | Serial.print("PAngle negative"); 837 | } else { 838 | PTposition[2] = {0x00}; 839 | } 840 | 841 | 842 | // Solve for Pan 843 | 844 | for (int8_t i = 8; i > 0; i--) { 845 | if (i - 2 > 2) { 846 | PTposition[i - 2] = PAngle % 16; //Add it to the Array 847 | } 848 | PAngle = (PAngle - PTposition[i - 2]) / 16; //Process the next part 849 | 850 | if ( PTposition[2] == 0x0F) { //If We are processing a negative angle striff off the F for VISCA 851 | switch (PTposition[i - 2]) { 852 | case 0x00: PTposition[i - 2] = 0x0F; break; 853 | case 0xF1: PTposition[i - 2] = 0x01; break; 854 | case 0xF2: PTposition[i - 2] = 0x02; break; 855 | case 0xF3: PTposition[i - 2] = 0x03; break; 856 | case 0xF4: PTposition[i - 2] = 0x04; break; 857 | case 0xF5: PTposition[i - 2] = 0x05; break; 858 | case 0xF6: PTposition[i - 2] = 0x06; break; 859 | case 0xF7: PTposition[i - 2] = 0x07; break; 860 | case 0xF8: PTposition[i - 2] = 0x08; break; 861 | case 0xF9: PTposition[i - 2] = 0x09; break; 862 | case 0xFA: PTposition[i - 2] = 0x0A; break; 863 | case 0xFB: PTposition[i - 2] = 0x0B; break; 864 | case 0xFC: PTposition[i - 2] = 0x0C; break; 865 | case 0xFD: PTposition[i - 2] = 0x0D; break; 866 | case 0xFE: PTposition[i - 2] = 0x0E; break; 867 | case 0xFF: PTposition[i - 2] = 0x0F; break; 868 | } 869 | } 870 | } 871 | 872 | 873 | // Solve for Tilt ****Tilt isstamping F on position2 Fix 874 | for (int8_t i = 12; i > 0; i--) { 875 | if (i - 2 > 6) { 876 | PTposition[i - 2] = TAngle % 16; 877 | } 878 | TAngle = (TAngle - PTposition[i - 2]) / 16; 879 | if ( TAngle < 0) { //If We are processing a negative angle striff off the F for VISCA 880 | switch (PTposition[i - 2]) { 881 | case 0xF1: PTposition[i - 2] = 0x01; break; 882 | case 0xF2: PTposition[i - 2] = 0x02; break; 883 | case 0xF3: PTposition[i - 2] = 0x03; break; 884 | case 0xF4: PTposition[i - 2] = 0x04; break; 885 | case 0xF5: PTposition[i - 2] = 0x05; break; 886 | case 0xF6: PTposition[i - 2] = 0x06; break; 887 | case 0xF7: PTposition[i - 2] = 0x07; break; 888 | case 0xF8: PTposition[i - 2] = 0x08; break; 889 | case 0xF9: PTposition[i - 2] = 0x09; break; 890 | case 0xFA: PTposition[i - 2] = 0x0A; break; 891 | case 0xFB: PTposition[i - 2] = 0x0B; break; 892 | case 0xFC: PTposition[i - 2] = 0x0C; break; 893 | case 0xFD: PTposition[i - 2] = 0x0D; break; 894 | case 0xFE: PTposition[i - 2] = 0x0E; break; 895 | case 0xFF: PTposition[i - 2] = 0x0F; break; 896 | } 897 | } 898 | 899 | } 900 | 901 | Serial.print("PTpos0: "); 902 | Serial.println(PTposition[0]); 903 | Serial.print("PTpos1: "); 904 | Serial.println(PTposition[1]); 905 | Serial.print("PTpos2: "); 906 | Serial.println(PTposition[2]); 907 | Serial.print("PTpos3: "); 908 | Serial.println(PTposition[3]); 909 | Serial.print("PTpos4: "); 910 | Serial.println(PTposition[4]); 911 | Serial.print("PTpos5: "); 912 | Serial.println(PTposition[5]); 913 | Serial.print("PTpos6: "); 914 | Serial.println(PTposition[6]); 915 | Serial.print("PTpos7: "); 916 | Serial.println(PTposition[7]); 917 | Serial.print("PTpos8: "); 918 | Serial.println(PTposition[8]); 919 | Serial.print("PTpos9: "); 920 | Serial.println(PTposition[9]); 921 | Serial.print("PTpos10: "); 922 | Serial.println(PTposition[10]); 923 | Serial.print("PTpos11: "); 924 | Serial.println(PTposition[11]); //Closing termonator 925 | 926 | // Solve for Focus 927 | 928 | FAngle = ((FAngle * 604.5) + 1000); //Because the Focus range is 1000-61440 929 | 930 | for (int8_t i = 7; i > 0; i--) { 931 | if (i - 2 > 1) { 932 | FocusPosition[i - 2] = FAngle % 16; //Add it to the Array 933 | } 934 | FAngle = (FAngle - FocusPosition[i - 2]) / 16; //Process the next part 935 | } 936 | Serial.print("Fpos0: "); 937 | Serial.println(FocusPosition[0]); 938 | Serial.print("Fpos1: "); 939 | Serial.println(FocusPosition[1]); 940 | Serial.print("Fpos2: "); 941 | Serial.println(FocusPosition[2]); 942 | Serial.print("Fpos3: "); 943 | Serial.println(FocusPosition[3]); 944 | Serial.print("Fpos4: "); 945 | Serial.println(FocusPosition[4]); 946 | Serial.print("Fpos5: "); 947 | Serial.println(FocusPosition[5]); 948 | Serial.print("Fpos6 -Should be 255: "); 949 | Serial.println(FocusPosition[6]); 950 | 951 | 952 | 953 | 954 | // Solve for Zoom 955 | 956 | ZAngle = (ZAngle * 60); //Because the zoom range is 0-6000 957 | 958 | for (int8_t i = 7; i > 0; i--) { 959 | if (i - 2 > 1) { 960 | ZoomPosition[i - 2] = ZAngle % 16; //Add it to the Array 961 | } 962 | ZAngle = (ZAngle - ZoomPosition[i - 2]) / 16; //Process the next part 963 | } 964 | ZoomPosition[6] = {0xFF}; 965 | Serial.print("ZPos0: "); 966 | Serial.println(ZoomPosition[0]); 967 | Serial.print("ZPos1: "); 968 | Serial.println(ZoomPosition[1]); 969 | Serial.print("ZPos2: "); 970 | Serial.println(ZoomPosition[2]); 971 | Serial.print("ZPos3: "); 972 | Serial.println(ZoomPosition[3]); 973 | Serial.print("ZPos4: "); 974 | Serial.println(ZoomPosition[4]); 975 | Serial.print("ZPos5: "); 976 | Serial.println(ZoomPosition[5]); 977 | Serial.print("ZPos6 should be 255: "); 978 | Serial.println(ZoomPosition[6]); 979 | 980 | 981 | 982 | 983 | // switch (PAngle) { 984 | // //Left 985 | // case 0: PTposition[2] = 0x00; PTposition[3] = 0x00; PTposition[4] = 0x00; PTposition[5] = 0x00; PTposition[6] = 0x00; break; 986 | // case 10: PTposition[2] = 0x00; PTposition[3] = 0x00; PTposition[4] = 0x09; PTposition[5] = 0x03; PTposition[6] = 0x07; break; 987 | // case 20: PTposition[2] = 0x00; PTposition[3] = 0x01; PTposition[4] = 0x02; PTposition[5] = 0x06; PTposition[6] = 0x0E; break; 988 | // case 30: PTposition[2] = 0x00; PTposition[3] = 0x01; PTposition[4] = 0x0B; PTposition[5] = 0x0A; PTposition[6] = 0x05; break; 989 | // case 40: PTposition[2] = 0x00; PTposition[3] = 0x02; PTposition[4] = 0x04; PTposition[5] = 0x0D; PTposition[6] = 0x0C; break; 990 | // case 50: PTposition[2] = 0x00; PTposition[3] = 0x02; PTposition[4] = 0x0E; PTposition[5] = 0x01; PTposition[6] = 0x03; break; 991 | // case 60: PTposition[2] = 0x00; PTposition[3] = 0x03; PTposition[4] = 0x07; PTposition[5] = 0x04; PTposition[6] = 0x0A; break; 992 | // case 70: PTposition[2] = 0x00; PTposition[3] = 0x04; PTposition[4] = 0x00; PTposition[5] = 0x08; PTposition[6] = 0x01; break; 993 | // case 80: PTposition[2] = 0x00; PTposition[3] = 0x04; PTposition[4] = 0x09; PTposition[5] = 0x0B; PTposition[6] = 0x08; break; 994 | // case 90: PTposition[2] = 0x00; PTposition[3] = 0x05; PTposition[4] = 0x02; PTposition[5] = 0x0E; PTposition[6] = 0x0F; break; 995 | // case 100: PTposition[2] = 0x00; PTposition[3] = 0x05; PTposition[4] = 0x0C; PTposition[5] = 0x02; PTposition[6] = 0x06; break; 996 | // case 110: PTposition[2] = 0x00; PTposition[3] = 0x00; PTposition[4] = 0x09; PTposition[5] = 0x03; PTposition[6] = 0x07; break; 997 | // case 120: PTposition[2] = 0x00; PTposition[3] = 0x06; PTposition[4] = 0x0E; PTposition[5] = 0x09; PTposition[6] = 0x04; break; 998 | // case 130: PTposition[2] = 0x00; PTposition[3] = 0x07; PTposition[4] = 0x07; PTposition[5] = 0x0C; PTposition[6] = 0x0B; break; 999 | // case 140: PTposition[2] = 0x00; PTposition[3] = 0x08; PTposition[4] = 0x01; PTposition[5] = 0x00; PTposition[6] = 0x02; break; 1000 | // case 150: PTposition[2] = 0x00; PTposition[3] = 0x08; PTposition[4] = 0x0A; PTposition[5] = 0x03; PTposition[6] = 0x09; break; 1001 | // case 160: PTposition[2] = 0x00; PTposition[3] = 0x09; PTposition[4] = 0x03; PTposition[5] = 0x07; PTposition[6] = 0x00; break; 1002 | // case 169: PTposition[2] = 0x00; PTposition[3] = 0x09; PTposition[4] = 0x0B; PTposition[5] = 0x0B; PTposition[6] = 0x0B; break; 1003 | // case 170: PTposition[2] = 0x00; PTposition[3] = 0x09; PTposition[4] = 0x0C; PTposition[5] = 0x0A; PTposition[6] = 0x07; break; 1004 | // // //Right 1005 | // case 1010: PTposition[2] = 0x0F; PTposition[3] = 0x0F; PTposition[4] = 0x06; PTposition[5] = 0x0C; PTposition[6] = 0x09; break; 1006 | // case 1020: PTposition[2] = 0x0F; PTposition[3] = 0x0E; PTposition[4] = 0x0D; PTposition[5] = 0x09; PTposition[6] = 0x02; break; 1007 | // case 1030: PTposition[2] = 0x0F; PTposition[3] = 0x0E; PTposition[4] = 0x04; PTposition[5] = 0x05; PTposition[6] = 0x0B; break; 1008 | // case 1040: PTposition[2] = 0x0F; PTposition[3] = 0x0D; PTposition[4] = 0x0B; PTposition[5] = 0x02; PTposition[6] = 0x04; break; 1009 | // case 1050: PTposition[2] = 0x0F; PTposition[3] = 0x0D; PTposition[4] = 0x01; PTposition[5] = 0x0E; PTposition[6] = 0x0D; break; 1010 | // case 1060: PTposition[2] = 0x0F; PTposition[3] = 0x0C; PTposition[4] = 0x08; PTposition[5] = 0x0B; PTposition[6] = 0x06; break; 1011 | // case 1070: PTposition[2] = 0x0F; PTposition[3] = 0x0B; PTposition[4] = 0x0F; PTposition[5] = 0x07; PTposition[6] = 0x0F; break; 1012 | // case 1080: PTposition[2] = 0x0F; PTposition[3] = 0x0B; PTposition[4] = 0x06; PTposition[5] = 0x04; PTposition[6] = 0x08; break; 1013 | // case 1090: PTposition[2] = 0x0F; PTposition[3] = 0x0A; PTposition[4] = 0x0D; PTposition[5] = 0x01; PTposition[6] = 0x01; break; 1014 | // case 1100: PTposition[2] = 0x0F; PTposition[3] = 0x0A; PTposition[4] = 0x03; PTposition[5] = 0x0D; PTposition[6] = 0x0A; break; 1015 | // case 1110: PTposition[2] = 0x0F; PTposition[3] = 0x09; PTposition[4] = 0x0A; PTposition[5] = 0x0A; PTposition[6] = 0x03; break; 1016 | // case 1120: PTposition[2] = 0x0F; PTposition[3] = 0x09; PTposition[4] = 0x01; PTposition[5] = 0x06; PTposition[6] = 0x0C; break; 1017 | // case 1130: PTposition[2] = 0x0F; PTposition[3] = 0x08; PTposition[4] = 0x08; PTposition[5] = 0x03; PTposition[6] = 0x05; break; 1018 | // case 1140: PTposition[2] = 0x0F; PTposition[3] = 0x07; PTposition[4] = 0x0E; PTposition[5] = 0x0F; PTposition[6] = 0x0E; break; 1019 | // case 1150: PTposition[2] = 0x0F; PTposition[3] = 0x07; PTposition[4] = 0x05; PTposition[5] = 0x0C; PTposition[6] = 0x07; break; 1020 | // case 1160: PTposition[2] = 0x0F; PTposition[3] = 0x06; PTposition[4] = 0x0C; PTposition[5] = 0x09; PTposition[6] = 0x00; break; 1021 | // case 1169: PTposition[2] = 0x0F; PTposition[3] = 0x06; PTposition[4] = 0x04; PTposition[5] = 0x04; PTposition[6] = 0x05; break; 1022 | // case 1170: PTposition[2] = 0x0F; PTposition[3] = 0x06; PTposition[4] = 0x03; PTposition[5] = 0x05; PTposition[6] = 0x09; break; 1023 | // } 1024 | // 1025 | // switch (TAngle) { 1026 | // // //UP 1027 | // case 0: PTposition[7] = 0x00; PTposition[8] = 0x00; PTposition[9] = 0x00; PTposition[10] = 0x00; break; 1028 | // case 10: PTposition[7] = 0x00; PTposition[8] = 0x09; PTposition[9] = 0x03; PTposition[10] = 0x07; break; 1029 | // case 20: PTposition[7] = 0x01; PTposition[8] = 0x02; PTposition[9] = 0x06; PTposition[10] = 0x0E; break; 1030 | // case 30: PTposition[7] = 0x01; PTposition[8] = 0x0B; PTposition[9] = 0x0A; PTposition[10] = 0x05; break; 1031 | // case 40: PTposition[7] = 0x02; PTposition[8] = 0x04; PTposition[9] = 0x0D; PTposition[10] = 0x0C; break; 1032 | // case 50: PTposition[7] = 0x02; PTposition[8] = 0x0E; PTposition[9] = 0x01; PTposition[10] = 0x03; break; 1033 | // case 60: PTposition[7] = 0x03; PTposition[8] = 0x07; PTposition[9] = 0x04; PTposition[10] = 0x0A; break; 1034 | // case 70: PTposition[7] = 0x04; PTposition[8] = 0x00; PTposition[9] = 0x08; PTposition[10] = 0x01; break; 1035 | // case 80: PTposition[7] = 0x04; PTposition[8] = 0x09; PTposition[9] = 0x0B; PTposition[10] = 0x08; break; 1036 | // case 90: PTposition[7] = 0x05; PTposition[8] = 0x02; PTposition[9] = 0x0E; PTposition[10] = 0x0F; break; 1037 | // // //Down 1038 | // case 1010: PTposition[7] = 0x0F; PTposition[8] = 0x06; PTposition[9] = 0x0C; PTposition[10] = 0x09; break; 1039 | // case 1020: PTposition[7] = 0x0E; PTposition[8] = 0x0D; PTposition[9] = 0x09; PTposition[10] = 0x02; break; 1040 | // case 1030: PTposition[7] = 0x0E; PTposition[8] = 0x04; PTposition[9] = 0x05; PTposition[10] = 0x0B; break; 1041 | // 1042 | // } 1043 | // 1044 | // switch (FAngle) { 1045 | // // //UP 1046 | // case 0: PTposition[7] = 0x00; PTposition[8] = 0x00; PTposition[9] = 0x00; PTposition[10] = 0x00; break; 1047 | // case 10: PTposition[7] = 0x00; PTposition[8] = 0x09; PTposition[9] = 0x03; PTposition[10] = 0x07; break; 1048 | // case 20: PTposition[7] = 0x01; PTposition[8] = 0x02; PTposition[9] = 0x06; PTposition[10] = 0x0E; break; 1049 | // case 30: PTposition[7] = 0x01; PTposition[8] = 0x0B; PTposition[9] = 0x0A; PTposition[10] = 0x05; break; 1050 | // case 40: PTposition[7] = 0x02; PTposition[8] = 0x04; PTposition[9] = 0x0D; PTposition[10] = 0x0C; break; 1051 | // case 50: PTposition[7] = 0x02; PTposition[8] = 0x0E; PTposition[9] = 0x01; PTposition[10] = 0x03; break; 1052 | // case 60: PTposition[7] = 0x03; PTposition[8] = 0x07; PTposition[9] = 0x04; PTposition[10] = 0x0A; break; 1053 | // case 70: PTposition[7] = 0x04; PTposition[8] = 0x00; PTposition[9] = 0x08; PTposition[10] = 0x01; break; 1054 | // case 80: PTposition[7] = 0x04; PTposition[8] = 0x09; PTposition[9] = 0x0B; PTposition[10] = 0x08; break; 1055 | // case 90: PTposition[7] = 0x05; PTposition[8] = 0x02; PTposition[9] = 0x0E; PTposition[10] = 0x0F; break; 1056 | // // //Down 1057 | // case 1010: PTposition[7] = 0x0F; PTposition[8] = 0x06; PTposition[9] = 0x0C; PTposition[10] = 0x09; break; 1058 | // case 1020: PTposition[7] = 0x0E; PTposition[8] = 0x0D; PTposition[9] = 0x09; PTposition[10] = 0x02; break; 1059 | // case 1030: PTposition[7] = 0x0E; PTposition[8] = 0x04; PTposition[9] = 0x05; PTposition[10] = 0x0B; break; 1060 | // 1061 | // } 1062 | 1063 | 1064 | 1065 | 1066 | 1067 | } 1068 | 1069 | 1070 | void GetUARTdata() { 1071 | static byte ndx = 0; 1072 | char endMarker = '\n'; 1073 | char rc; 1074 | 1075 | while (UARTport.available() ) { 1076 | rc = UARTport.read(); 1077 | if (rc != endMarker) { 1078 | receivedChars[ndx] = rc; 1079 | ndx++; 1080 | if (ndx > numChars) { 1081 | ndx = numChars - 1; 1082 | } 1083 | } 1084 | else { 1085 | receivedChars[ndx] = '\0'; // terminate the string 1086 | ndx = 0; 1087 | newData = true; 1088 | } 1089 | } 1090 | } 1091 | 1092 | 1093 | //At startup get the current IP adress from rthe main processor 1094 | void GetIP() { 1095 | Serial.println ("Listening"); 1096 | char buffer[30]; 1097 | delay(500); 1098 | int SYS1 = 665; 1099 | int SYS2 = 666; 1100 | int SYS3 = 667; 1101 | int SYS4 = 668; 1102 | int SYS5 = 669; 1103 | int SYS6 = 670; 1104 | static byte ndx = 0; 1105 | char endMarker = '\n'; 1106 | char rc; 1107 | 1108 | sprintf(buffer, "%d\n", SYS1 ); //Gget IP1 1109 | UARTport.print(buffer); 1110 | UARTport.flush(); 1111 | newData = false; 1112 | delay(50); 1113 | GetUARTdata(); 1114 | if (newData == true) { 1115 | IP1 = atoi(receivedChars); 1116 | 1117 | Serial.print("IP1: "); 1118 | Serial.println(IP1); 1119 | } 1120 | sprintf(buffer, "%d\n", SYS2 ); //Gget IP2 1121 | UARTport.print(buffer); 1122 | UARTport.flush(); 1123 | newData = false; 1124 | delay(50); 1125 | GetUARTdata(); 1126 | if (newData == true) { 1127 | IP2 = atoi(receivedChars); 1128 | 1129 | Serial.print("IP2: "); 1130 | Serial.println(IP2); 1131 | } 1132 | sprintf(buffer, "%d\n", SYS3 ); //Gget IP3 1133 | UARTport.print(buffer); 1134 | UARTport.flush(); 1135 | newData = false; 1136 | delay(50); 1137 | GetUARTdata(); 1138 | if (newData == true) { 1139 | IP3 = atoi(receivedChars); 1140 | 1141 | Serial.print("IP3: "); 1142 | Serial.println(IP3); 1143 | } 1144 | sprintf(buffer, "%d\n", SYS4 ); //Gget IP4 1145 | UARTport.print(buffer); 1146 | UARTport.flush(); 1147 | newData = false; 1148 | delay(50); 1149 | GetUARTdata(); 1150 | if (newData == true) { 1151 | IP4 = atoi(receivedChars); 1152 | 1153 | Serial.print("IP4: "); 1154 | Serial.println(IP4); 1155 | } 1156 | 1157 | sprintf(buffer, "%d\n", SYS6 ); //Gget IPGW the server gatway 1158 | UARTport.print(buffer); 1159 | UARTport.flush(); 1160 | newData = false; 1161 | delay(50); 1162 | GetUARTdata(); 1163 | if (newData == true) { 1164 | IPGW = atoi(receivedChars); 1165 | 1166 | Serial.print("IPGW: "); 1167 | Serial.println(IPGW); 1168 | } 1169 | 1170 | sprintf(buffer, "%d\n", SYS5 ); //Gget UDPport 1171 | UARTport.print(buffer); 1172 | UARTport.flush(); 1173 | newData = false; 1174 | delay(50); 1175 | GetUARTdata(); 1176 | if (newData == true) { 1177 | UDP = atoi(receivedChars); 1178 | 1179 | Serial.print("UDPport: "); 1180 | Serial.println(UDP); 1181 | } 1182 | } 1183 | 1184 | void ReadInPTpos() { //Read in the Absolute position request PT only 1185 | //Convert Pan back to Dec Degrees for input 1186 | 1187 | Serial.print("NumHex7: "); 1188 | Serial.println(NumHex7); 1189 | Serial.print("NumHex8: "); 1190 | Serial.println(NumHex8); 1191 | Serial.print("NumHex9: "); 1192 | Serial.println(NumHex9); 1193 | Serial.print("NumHex10: "); 1194 | Serial.println(NumHex10); 1195 | char buffer[30]; 1196 | sprintf(buffer, "0x%s%s%s%s", NumHex7, NumHex8, NumHex9, NumHex10); 1197 | String Hstring = (buffer); 1198 | Serial.println(Hstring); 1199 | 1200 | char H_array[7]; 1201 | Hstring.toCharArray(H_array, 7); 1202 | int x; 1203 | char *endptr; 1204 | x = strtol(H_array, &endptr, 16); 1205 | Serial.println(x, HEX); 1206 | Serial.println(x, DEC); 1207 | 1208 | if ( x >= 23090) { //If the move is negatvie 1209 | PAngleIn = (x - 23090); //Stored int16_t to provide a signed 2's value NOT REQUIRED 1210 | PAngleIn = 180 - ((PAngleIn / 235.9) ); 1211 | PAngleIn = (PAngleIn - (PAngleIn * 2)); //Sign it as negative 1212 | Serial.print("PAngleIn: "); 1213 | Serial.println(PAngleIn); 1214 | } else { 1215 | PAngleIn = x; 1216 | PAngleIn = ((PAngleIn / 117.95)); 1217 | 1218 | Serial.print("PAngleIn: "); 1219 | Serial.println(PAngleIn); 1220 | } 1221 | 1222 | 1223 | //Convert Tilt back to Dec Degrees for input 1224 | 1225 | Serial.print("NumHex11: "); 1226 | Serial.println(NumHex11); 1227 | Serial.print("NumHex12: "); 1228 | Serial.println(NumHex12); 1229 | Serial.print("NumHex13: "); 1230 | Serial.println(NumHex13); 1231 | Serial.print("NumHex14: "); 1232 | Serial.println(NumHex14); 1233 | //char buffer[30]; 1234 | sprintf(buffer, "0x%s%s%s%s", NumHex11, NumHex12, NumHex13, NumHex14); //Send the requested PT vMix position to the head 1235 | Hstring = (buffer); 1236 | Serial.println(Hstring); 1237 | 1238 | //char H_array[7]; 1239 | Hstring.toCharArray(H_array, 7); 1240 | x; 1241 | //char *endptr; 1242 | x = strtol(H_array, &endptr, 16); 1243 | Serial.println(x, HEX); 1244 | Serial.println(x, DEC); 1245 | TAngleIn = x; //Stored int16_t to provide a signed 2's value not required 1246 | if (TAngleIn > 43000) { //Then the move is negative down 1247 | TAngleIn = (x - 23090); //Stored int16_t to provide a signed 2's value 1248 | TAngleIn = 180 - ((TAngleIn / 235.9) ); 1249 | TAngleIn = (TAngleIn - (TAngleIn * 2)); //Sign it as negative 1250 | Serial.print("TAngleIn: "); 1251 | Serial.println(TAngleIn); 1252 | } else { 1253 | TAngleIn = ((TAngleIn / 235.9)); 1254 | Serial.print("TAngleIn: "); 1255 | Serial.println(TAngleIn); 1256 | } 1257 | } 1258 | void ReadInZoomFocus() { //Read in the Absolute position request PT only 1259 | //Convert Zoom back to % of Zoom 1260 | 1261 | Serial.print("NumHex4: "); 1262 | Serial.println(NumHex4); 1263 | Serial.print("NumHex5: "); 1264 | Serial.println(NumHex5); 1265 | Serial.print("NumHex6: "); 1266 | Serial.println(NumHex6); 1267 | Serial.print("NumHex7: "); 1268 | Serial.println(NumHex7); 1269 | char buffer[30]; 1270 | sprintf(buffer, "0x%s%s%s%s", NumHex4, NumHex5, NumHex6, NumHex7); //Send the vMix zoom request to the head 1271 | String Hstring = (buffer); 1272 | Serial.println(Hstring); 1273 | 1274 | char H_array[7]; 1275 | Hstring.toCharArray(H_array, 7); 1276 | int x; 1277 | char *endptr; 1278 | x = strtol(H_array, &endptr, 16); 1279 | Serial.println(x, HEX); 1280 | Serial.println(x, DEC); 1281 | 1282 | ZAngleIn = x; 1283 | ZAngleIn = ZAngleIn / 60; 1284 | 1285 | Serial.print("ZAngleIn: "); 1286 | Serial.println(ZAngleIn); 1287 | 1288 | 1289 | 1290 | //Convert Focus back to % of focus for input 1291 | 1292 | Serial.print("NumHex8: "); 1293 | Serial.println(NumHex8); 1294 | Serial.print("NumHex9: "); 1295 | Serial.println(NumHex9); 1296 | Serial.print("NumHex10: "); 1297 | Serial.println(NumHex10); 1298 | Serial.print("NumHex11: "); 1299 | Serial.println(NumHex11); 1300 | //char buffer[30]; 1301 | sprintf(buffer, "0x%s%s%s%s", NumHex8, NumHex9, NumHex10, NumHex11); //Send the focus position to the head 1302 | Hstring = (buffer); 1303 | Serial.println(Hstring); 1304 | 1305 | //char H_array[7]; 1306 | Hstring.toCharArray(H_array, 7); 1307 | x; 1308 | 1309 | x = strtol(H_array, &endptr, 16); 1310 | Serial.println(x, HEX); 1311 | Serial.println(x, DEC); 1312 | FAngleIn = x; //Stored int16_t to provide a signed 2's value not required 1313 | FAngleIn = (FAngleIn - 1000) / 604.5; //Convert bake to % of posible move 1314 | 1315 | 1316 | Serial.print("FAngleIn: "); 1317 | Serial.println(FAngleIn); 1318 | } 1319 | -------------------------------------------------------------------------------- /PTZplus_WIFI_Controller/Digital Bird PTZplus WIFI Control Quickstart V6.03.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/PTZplus_WIFI_Controller/Digital Bird PTZplus WIFI Control Quickstart V6.03.pdf -------------------------------------------------------------------------------- /PTZplus_WIFI_Controller/Nextion_PTZplusControl-6.03-Basic.tft: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/PTZplus_WIFI_Controller/Nextion_PTZplusControl-6.03-Basic.tft -------------------------------------------------------------------------------- /PTZplus_WIFI_Controller/Nextion_PTZplusControl-6.03-Disc.tft: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/PTZplus_WIFI_Controller/Nextion_PTZplusControl-6.03-Disc.tft -------------------------------------------------------------------------------- /PTZplus_WIFI_Controller/Nextion_PTZplusControl-6.03-En.tft: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/PTZplus_WIFI_Controller/Nextion_PTZplusControl-6.03-En.tft -------------------------------------------------------------------------------- /PTZplus_WIFI_Controller/ReadMe: -------------------------------------------------------------------------------- 1 | update 6.05 Fixed a bug where shutter speed was not being respected in time-lapse mode 2 | update 6.04: Fixes a bug where Ease values were not being updated correctly 3 | update 6.03 adds a new funtion "All To Pose" to the PTZ menu. This allows you to have all cameras move to the current pose/preset number at the same time with one button press. 4 | 5 | 6 | There are three possible 2.8" Nextion displays that can be used by the system BASIC, DISCOVERY, ENHANCED 7 | Thay can be identified from the colour of the PCB board on the display. 8 | Blue-Basic 9 | Orange-Discovery 10 | Black- Enhanced 11 | 12 | For our purposes they all work the same but the firmware requires you install for the specific model 13 | Hense the reason there are three Nextion files here 14 | 15 | 16 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | # DigitalBird Camera motion control system 5 | 6 | 7 | Professional level DIY Camera Motion Control System 8 | This repository is for all the software used to drive the Digital bird camera motion control system. 9 | This projects aim is to provide the most feature rich DIY camera motion control system on the internet. 10 | 11 | All of the 3D printed parts can be found on the Printables or Thingiverse website and I Supply kits for all the non 3D Print parts 12 | including pre programed PCB main boards on the Digital Bird shoppify channel. No soldering or programming required. 13 | 14 | Also check out the Digital Bird Youtube and Autodesk Instructables website for detailed build instructions. 15 | 16 | Currently the system consists of 7 parts. The Slider, a choice of 3 Pan Tilt Heads , Cinematic Turntable, Focus motor, compact WIFI controller 17 | PTZplus WIFI Controller and the mini jib. Any of the parts can be used indevidually or together and are all controled from the Single WIFI remote. 18 | 19 | The system offers the following functionality: 20 | * A-B straight moves with ease or ramp, bounce, and timlapse control. 21 | * 6 Key sequencer control for more complex moves 22 | * Basic stop motion animation functions 23 | * 3 camera PTZplus control for realtime camera control with each camera system able to store 6 key poses 24 | * The New DB3 PTZ head also supports VISCA over IP with support for OBS & vMix 25 | 26 | 27 | All parts of the system use the ESP32 processor 28 | For detailed Instructions on how to install this software read the file titled "DigitalBird-Software Installation Guide.pdf" 29 | The first step is to click on the green "CODE" button and select download ZIP, Unpack the zip to your computer but do not unpack the library zips included inside it. 30 | Then follow the instruction in the aforementioned .pdf which will come down with the code 31 | 32 | Note there are currently two different .ino files for the pan Tilt head. The one ending in OT should be used for the original over the top model. The one ending B is for the newer balanced model. The only real differance is speed settings to compensate for the differing gear ratios on the different models. 33 | If you are updating software from previose versions please note that you will have to update all parts of the system at the same time in order for them to stay compatable. 34 | 35 | WARNING Notice: 36 | If updating the code on the built device be sure to remove the battery from the device before you plug in the usb cable. 37 | Failure too do so may fry your ESP32 with to much power and also damage your PC usb port. 38 | I will not be held liable for either. This is generally the case with all project boards. 39 | 40 | # Software Updates: 41 | 42 | IMPORTANT NOTE: When installing the esp32 boards through the board manager be sure to install version 2.011 (Not the latest update) I canot keep up with all the latest library updates so remember also to use the library's provided here not the latest updates which may not work with the system. 43 | 44 | 45 | 46 | Update Notes v6.00: 23rd Oct 2023 47 | 48 | 1) Now supports up to four WIFI camera systems rather than the original three. 49 | 2) Also know supports 9 pose/preset positions over the original 6. 16 are available for wired VISCA control 50 | 3) Two poses 15 & 16 have been reserved in order to allow triggering of the current A-B and sequencer setups with or withought bounce. 51 | these can also be triggered from VISCA by calling pose 15 or 16 respectivly. 52 | 4) The setup menu also now alows you to set a delay at the start and end of bounce moves. This also sets a recording pause at the end of A-B moves 53 | before the system returns to its home position. The pause can be 1-10 seconds. This setting is stored in memorry and recalled on reboot. 54 | 5) A number of small bugs have been fixed along the way however I am unsure which of these were in the last version and which were required as 55 | a result of the added functionality so I will not list. 56 | 6) ESP32 board updates were giving issues with the encoders this has know been fixed and we are know able to compile the code with Arduino IDE 2.* 57 | 7) The application also now uses the currently current! FastAccelStepper library. 58 | 8) Firmware numbering has been updated across the system. To keep things simple all parts of the system must be running the first part of the version number so this update is 6. 59 | If indevidual parts of the system require an update which does not effect the other parts this can happen as here v6.02. The first number "6" will only increment if the update effect all parts of the system 60 | and it will increment on all firmware parts. So in the case of this update all parts of the system must be updated to v6.** stay compatable. 61 | 62 | 63 | -------------------------------------------------------------------------------- /arduino-AS5600-master.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/digitalbird01/DigitalBird-Camera-Slider/dfebf61716152b31b966f019a68e993d16f25c75/arduino-AS5600-master.zip -------------------------------------------------------------------------------- /githold: -------------------------------------------------------------------------------- 1 | 2 | --------------------------------------------------------------------------------