halb-broken implementation with other dmx driver. out works only on second port, in works on first port very slowly and on the second port fast

This commit is contained in:
Patrick Schwarz 2025-02-01 22:49:24 +01:00
parent 5870182507
commit 4b811187f7
5 changed files with 202 additions and 151 deletions

View file

@ -18,6 +18,16 @@ board_build.filesystem = littlefs
[env:lolin_s2_mini]
platform = espressif32
board = lolin_s2_mini
lib_deps =
lib_deps =
bblanchon/ArduinoJson @ ^7.2.0
someweisguy/esp_dmx
extra_scripts = pre:pre_extra_script.py
;build_type = debug
;build_flags = -DCORE_DEBUG_LEVEL=5
;upload_port = COM4
monitor_port = COM4
[env:esp32_wroom_32]
platform = espressif32
board = nodemcu-32s
lib_deps = bblanchon/ArduinoJson @ ^7.2.0

View file

@ -1,83 +0,0 @@
/* ----- LIBRARIES ----- */
#include <Arduino.h>
#include "ESPDMX.h"
// DMX value array and size. Entry 0 will hold startbyte, so we need 512+1 elements
// std::vector<uint8_t[DMXCHANNELS + 1]> dmxDataStores(MAX_IDS);
// uint8_t dmxDataStores[MAX_IDS][DMXCHANNELS + 1];
// Set up the DMX-Protocol
void DMXESPSerial::init(int pinSend = DMX_DEFAULT_TX, int pinRecv = DMX_DEFAULT_RX, HardwareSerial& port = DMX_DEFAULT_PORT)
{
sendPin = pinSend;
recvPin = pinRecv;
_Serial = &port;
_Serial->begin(DMXSPEED, DMXFORMAT, recvPin, sendPin);
Serial.print("Init DMX with pins (TX/RX): ");
Serial.print(sendPin);
Serial.print("/");
Serial.println(recvPin);
pinMode(sendPin, OUTPUT);
dmxStarted = true;
}
// Function to read DMX data
uint8_t DMXESPSerial::read(int channel)
{
if (dmxStarted == false)
init();
if (channel < 1)
channel = 1;
if (channel > DMXCHANNELS)
channel = DMXCHANNELS;
return (dmxDataStore[channel]);
}
uint8_t* DMXESPSerial::readAll()
{
if (dmxStarted == false)
init();
return (&dmxDataStore[1]);
}
// Function to send DMX data
void DMXESPSerial::write(int channel, uint8_t value)
{
if (dmxStarted == false)
init();
if (channel < 1)
channel = 1;
if (channel > DMXCHANNELS)
channel = DMXCHANNELS;
dmxDataStore[channel] = value;
}
void DMXESPSerial::end()
{
_Serial->end();
}
// Function to update the DMX bus
void DMXESPSerial::update()
{
// Send break
digitalWrite(sendPin, HIGH);
_Serial->begin(BREAKSPEED, BREAKFORMAT, recvPin, sendPin);
_Serial->write(0);
_Serial->flush();
delay(1);
_Serial->end();
// send data
_Serial->begin(DMXSPEED, DMXFORMAT, recvPin, sendPin);
digitalWrite(sendPin, LOW);
_Serial->write(dmxDataStore, DMXCHANNELS);
_Serial->flush();
delay(1);
_Serial->end();
}

View file

@ -1,37 +0,0 @@
#include <inttypes.h>
#include <HardwareSerial.h>
#ifndef ESPDMX_h
#define ESPDMX_h
#define DMXSPEED 250000
#define DMXFORMAT SERIAL_8N2
#define BREAKSPEED 83333
#define BREAKFORMAT SERIAL_8N1
#define DMX_DEFAULT_PORT Serial0
#define DMX_DEFAULT_TX 21
#define DMX_DEFAULT_RX 33
#define DMXCHANNELS 512
class DMXESPSerial
{
public:
int sendPin;
int recvPin;
HardwareSerial *port;
bool dmxStarted;
uint8_t dmxDataStore[DMXCHANNELS + 1];
void init(int pinSend, int pinRecv, HardwareSerial& port);
uint8_t read(int channel);
uint8_t* readAll();
void write(int channel, uint8_t value);
void update();
void end();
private:
// Member variables
HardwareSerial* _Serial;
};
#endif

View file

@ -1,6 +1,9 @@
#ifdef ESP32
#include <WiFi.h>
#include <AsyncTCP.h>
//#include <USB.h>
//#include "USBCDC.h"
#include "driver/temp_sensor.h"
#elif defined(ESP8266)
#include <ESP8266WiFi.h>
#include <ESPAsyncTCP.h>
@ -13,13 +16,24 @@
#include <ArtnetWiFi.h>
#include <ArduinoJson.h>
#include "ESPDMX.h"
//#include "ESPDMX.h"
#include <Arduino.h>
#include <esp_dmx.h>
#include <LittleFS.h>
#include "routes/config.h"
#include "routes/networks.h"
DMXESPSerial dmx1;
DMXESPSerial dmx2;
//DMXESPSerial dmx1;
//DMXESPSerial dmx2;
dmx_port_t dmx1 = DMX_NUM_0; // for esp32s2
dmx_port_t dmx2 = DMX_NUM_1;
byte dmx1_data[DMX_PACKET_SIZE];
byte dmx2_data[DMX_PACKET_SIZE];
unsigned long dmx1_lastUpdate = millis();
unsigned long dmx2_lastUpdate = millis();
bool dmx1_IsConnected = false;
bool dmx2_IsConnected = false;
// Button
#define PIN_LED 7
@ -53,7 +67,7 @@ void IRAM_ATTR onTimer()
#define ETH_INT 38
#define ETH_SPI_HOST SPI2_HOST
#define ETH_SPI_CLOCK_MHZ 25
byte mac[6] = {0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED};
byte mac[6];
AsyncWebServer server(80);
@ -64,8 +78,6 @@ uint8_t universe1;
uint8_t universe2;
Direction direction1;
Direction direction2;
// const uint16_t size = 512;
// uint8_t data[DMXCHANNELS];
void ledBlink(int ms)
{
@ -87,12 +99,36 @@ void ledBlink(int ms)
}
}
float getTemperature()
{
float tempC = -1.0f;
temp_sensor_read_celsius(&tempC);
return tempC;
}
void setup()
{
Serial.begin(9600);
// Get ETH mac
delay(1000);
esp_efuse_mac_get_default(mac);
esp_read_mac(mac, ESP_MAC_ETH);
Serial.printf("%02x:%02x:%02x:%02x:%02x:%02x ESP MAC ETH\n",
mac[0], mac[1], mac[2],
mac[3], mac[4], mac[5]);
esp_read_mac(mac, ESP_MAC_WIFI_SOFTAP);
Serial.printf("%02x:%02x:%02x:%02x:%02x:%02x ESP MAC SOFTAP\n",
mac[0], mac[1], mac[2],
mac[3], mac[4], mac[5]);
esp_read_mac(mac, ESP_MAC_WIFI_STA); //ESP_MAC_BASE
Serial.printf("%02x:%02x:%02x:%02x:%02x:%02x ESP MAC BASE\n",
mac[0], mac[1], mac[2],
mac[3], mac[4], mac[5]);
// LED
config.begin("dmx", true);
@ -186,6 +222,8 @@ void setup()
Serial.println(WiFi.localIP());
Serial.print("MAC address: ");
Serial.println(WiFi.macAddress());
Serial.print("Broadcast IP: ");
Serial.println(broadcastIp);
break;
case Ethernet:
@ -233,6 +271,8 @@ void setup()
Serial.println(ETH.dnsIP());
Serial.print("MAC address : ");
Serial.println(ETH.macAddress());
Serial.print("Broadcast IP: ");
Serial.println(broadcastIp);
Serial.println("Ethernet Successfully Initialized");
break;
}
@ -247,39 +287,86 @@ void setup()
Serial.println(WiFi.softAPIP());
Serial.print("MAC address: ");
Serial.println(WiFi.softAPmacAddress());
Serial.print("Broadcast IP: ");
Serial.println(broadcastIp);
break;
}
// Initialize DMX ports
Serial.println("Initialize DMX...");
dmx1.init(21, 33, Serial0);
dmx2.init(17, 18, Serial1);
#ifdef CONFIG_IDF_TARGET_ESP32S2
//dmx1.init(21, 33, Serial0);
//dmx2.init(17, 18, Serial1);
Serial.print("DMX driver 1 installed: ");
Serial.println(dmx_driver_is_installed(dmx1));
Serial.print("DMX driver 2 installed: ");
Serial.println(dmx_driver_is_installed(dmx2));
dmx_config_t dmx_config = DMX_CONFIG_DEFAULT;
dmx_personality_t personalities[] = {};
/*dmx_personality_t personalities[] = {
{1, "Default Personality"}
};*/
/*int personality_count = 1;*/
int personality_count = 0;
dmx_driver_install(dmx1, &dmx_config, personalities, personality_count);
dmx_set_pin(dmx1, 21, 33, -1);
dmx_driver_install(dmx2, &dmx_config, personalities, personality_count);
dmx_set_pin(dmx2, 17, 18, -1);
Serial.print("DMX driver 1 installed: ");
Serial.println(dmx_driver_is_installed(dmx1));
Serial.print("DMX driver 2 installed: ");
Serial.println(dmx_driver_is_installed(dmx2));
Serial.print("DMX driver 1 enabled: ");
Serial.println(dmx_driver_is_enabled(dmx1));
Serial.print("DMX driver 2 enabled: ");
Serial.println(dmx_driver_is_enabled(dmx2));
// TX/RX Pins und Serial0/Serial1 ausgeben
/* Now set the DMX hardware pins to the pins that we want to use and setup
will be complete! */
#else
dmx1.init(21, 33, Serial1);
dmx2.init(17, 18, Serial2);
#endif
// Initialize Art-Net
Serial.println("Initialize Art-Net...");
artnet.begin();
// if Artnet packet comes to this universe, this function is called
if (direction1 == Output)
if (direction1 == Output)
{
Serial.println("DMX1 as out");
artnet.subscribeArtDmxUniverse(universe1, [&](const uint8_t *data, uint16_t size, const ArtDmxMetadata &metadata, const ArtNetRemoteInfo &remote)
{
for (size_t i = 0; i < size; ++i)
{
dmx1.write((i + 1), data[i]);
}
dmx1.update(); });
{
dmx_write_offset(dmx1, 1, data, size);
dmx_send(dmx1);
dmx_wait_sent(dmx1, DMX_TIMEOUT_TICK);
});
}
if (direction2 == Output)
{
Serial.println("DMX2 as out");
artnet.subscribeArtDmxUniverse(universe2, [&](const uint8_t *data, uint16_t size, const ArtDmxMetadata &metadata, const ArtNetRemoteInfo &remote)
{
for (size_t i = 0; i < size; ++i)
{
dmx2.write((i + 1), data[i]);
}
dmx2.update(); });
{
dmx_write_offset(dmx2, 1, data, size);
dmx_send(dmx2);
dmx_wait_sent(dmx2, DMX_TIMEOUT_TICK);
});
}
// if Artnet packet comes, this function is called to every universe
@ -325,6 +412,26 @@ void setup()
WiFi.scanNetworks(true);
ledBlink(0);
// Internal temperature RP2040
/*float tempC = analogReadTemp(); // Get internal temperature
Serial.print("Temperature Celsius (ºC): ");
Serial.println(tempC);*/
// Internal temperature ESP32 https://www.espboards.dev/blog/esp32-inbuilt-temperature-sensor/
Serial.print("Temperature: ");
float result = 0;
temp_sensor_read_celsius(&result);
Serial.print(result);
Serial.println(" °C");
Serial.print(getTemperature());
Serial.println(" °C");
Serial.printf("Internal Total heap %d, internal Free Heap %d\n", ESP.getHeapSize(), ESP.getFreeHeap());
Serial.printf("SPIRam Total heap %d, SPIRam Free Heap %d\n", ESP.getPsramSize(), ESP.getFreePsram());
Serial.printf("ChipRevision %d, Cpu Freq %d, SDK Version %s\n", ESP.getChipRevision(), ESP.getCpuFreqMHz(), ESP.getSdkVersion());
Serial.printf("Flash Size %d, Flash Speed %d\n", ESP.getFlashChipSize(), ESP.getFlashChipSpeed());
}
void loop()
@ -332,14 +439,69 @@ void loop()
// check if artnet packet has come and execute callback
artnet.parse();
// Receive Callback/INT currently not implemented
/*if (direction1 == Input) {
artnet.setArtDmxData(dmx1.readAll(), DMXCHANNELS);
artnet.streamArtDmxTo(broadcastIp, universe1);
/* We need a place to store information about the DMX packets we receive. We
will use a dmx_packet_t to store that packet information. */
dmx_packet_t dmx1_packet;
dmx_packet_t dmx2_packet;
/* And now we wait! The DMX standard defines the amount of time until DMX
officially times out. That amount of time is converted into ESP32 clock
ticks using the constant `DMX_TIMEOUT_TICK`. If it takes longer than that
amount of time to receive data, this if statement will evaluate to false. */
if (direction1 == Input) {
//Serial.println("Recv DMX1");
/* If this code gets called, it means we've received DMX data! */
dmx_read_offset(dmx1, 1, dmx1_data, 512);
artnet.sendArtDmx(broadcastIp, universe1, dmx1_data, 512);
}
if (direction2 == Input) {
artnet.setArtDmxData(dmx2.readAll(), DMXCHANNELS);
artnet.streamArtDmxTo(broadcastIp, universe2);
}*/
if (direction2 == Input && dmx_receive(dmx2, &dmx2_packet, DMX_TIMEOUT_TICK)) {
//Serial.println("Recv DMX2");
/* If this code gets called, it means we've received DMX data! */
dmx_read_offset(dmx2, 1, dmx2_data, 512);
artnet.sendArtDmx(broadcastIp, universe2, dmx2_data, 512);
/* Get the current time since boot in milliseconds so that we can find out
how long it has been since we last updated data and printed to the Serial
Monitor. */
unsigned long now = millis();
/* We should check to make sure that there weren't any DMX errors. */
if (!dmx2_packet.err) {
/* If this is the first DMX data we've received, lets log it! */
if (!dmx2_IsConnected) {
Serial.println("DMX2 in is connected!");
dmx2_IsConnected = true;
}
/* Don't forget we need to actually read the DMX data into our buffer so
that we can print it out. */
/*dmx_read_offset(dmx2, 1, dmx2_data, dmx2_packet.size);
artnet.sendArtDmx(broadcastIp, universe2, dmx2_data, 512);*/
if (now - dmx2_lastUpdate > 1000) {
/* Print the received start code - it's usually 0. */
//Serial.printf("Start code is 0x%02X and slot 1 is 0x%02X\n", dmx2_data[0], dmx2_data[1]);
dmx2_lastUpdate = now;
}
} else {
/* Oops! A DMX error occurred! Don't worry, this can happen when you first
connect or disconnect your DMX devices. If you are consistently getting
DMX errors, then something may have gone wrong with your code or
something is seriously wrong with your DMX transmitter. */
Serial.println("A DMX 2 error occurred.");
}
} else if (dmx2_IsConnected) {
/* If DMX times out after having been connected, it likely means that the
DMX cable was unplugged. When that happens in this example sketch, we'll
uninstall the DMX driver. */
Serial.println("DMX 2 was disconnected.");
dmx2_IsConnected = false;
//dmx_driver_delete(dmx2);
}
}

View file

@ -1,5 +1,4 @@
#include <AsyncWebServer_ESP32_W5500.h>
#include <ESPDMX.h>
#include <Preferences.h>
#ifndef CONFIG_h