This commit is contained in:
Serge NOEL
2026-02-10 11:27:18 +01:00
parent 549c9f388e
commit 4423bb2de1
175 changed files with 238087 additions and 0 deletions

BIN
Railuino/src/.DS_Store vendored Normal file

Binary file not shown.

86
Railuino/src/Config.h Normal file
View File

@@ -0,0 +1,86 @@
/*********************************************************************
* Railuino - Hacking your Märklin
*
* Copyright (C) 2012 Joerg Pleumann
* Copyright (C) 2024 christophe bobille
*
* This example is free software; you can redistribute it and/or
* modify it under the terms of the Creative Commons Zero License,
* version 1.0, as published by the Creative Commons Organisation.
* This effectively puts the file into the public domain.
*
* This example is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* LICENSE file for more details.
*/
#ifndef CONFIG_H
#define CONFIG_H
// ===================================================================
// === Common definitions ============================================
// ===================================================================
/**
* Version of Railuino library and required connection box software.
*/
//#define RAILUINO_VERSION 0x005B // 0.91 -> upgrade 0.90 to 0.91 christophe bobille 2024
//#define RAILUINO_VERSION 0x005C // 0.92 -> upgrade 0.91 to 0.92 christophe bobille 17/07/2024
//#define RAILUINO_VERSION 0x005D // 0.93 -> upgrade 0.92 to 0.93 christophe bobille 2024
#define RAILUINO_VERSION 0x3AD // 0.941 -> upgrade 0.93 to 0.94 for Arduino christophe bobille 03/2025
#define TRACKBOX_VERSION 0x0127 // 1.39
/**
* Constants for protocol base addresses.
*/
#define ADDR_MM2 0x0000 // MM2 locomotive
#define ADDR_SX1 0x0800 // Selectrix (old) locomotive
#define ADDR_MFX 0x4000 // MFX locomotive
#define ADDR_SX2 0x8000 // Selectrix (new) locomotive
#define ADDR_DCC 0xC000 // DCC locomotive
#define ADDR_ACC_SX1 0x2000 // Selectrix (old) magnetic accessory
#define ADDR_ACC_MM2 0x2FFF // MM2 magnetic accessory
#define ADDR_ACC_DCC 0x3800 // DCC magnetic accessory
/**
* Constants for classic MM2 Delta addresses.
*/
#define DELTA1 78
#define DELTA2 72
#define DELTA3 60
#define DELTA4 24
/**
* Constants for locomotive directions.
*/
#define DIR_CURRENT 0
#define DIR_FORWARD 1
#define DIR_REVERSE 2
#define DIR_CHANGE 3
/**
* Constants for accessory states including some aliases.
*/
#define ACC_OFF 0
#define ACC_ROUND 0
#define ACC_RED 0
#define ACC_RIGHT 0
#define ACC_HP0 0
#define ACC_ON 1
#define ACC_GREEN 1
#define ACC_STRAIGHT 1
#define ACC_HP1 1
#define ACC_YELLOW 2
#define ACC_LEFT 2
#define ACC_HP2 2
#define ACC_WHITE 3
#define ACC_SH0 3
#endif // CONFIG_H

View File

@@ -0,0 +1,890 @@
/*********************************************************************
* Railuino - Hacking your Märklin
*
* Copyright (C) 2012 Joerg Pleumann
* Copyright (C) 2024 christophe bobille
*
* This example is free software; you can redistribute it and/or
* modify it under the terms of the Creative Commons Zero License,
* version 1.0, as published by the Creative Commons Organisation.
* This effectively puts the file into the public domain.
*
* This example is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* LICENSE file for more details.
*/
#include "TrackController.h"
#if defined ARDUINO_ARCH_ESP32
#include <ACAN_ESP32.h> // https://github.com/pierremolinaro/acan-esp32.git
#include <Arduino.h>
#elif defined ARDUINO_ARCH_AVR
#include <ACAN2515.h> // https://github.com/pierremolinaro/acan2515.git
static const uint32_t QUARTZ_FREQUENCY = 16UL * 1000UL * 1000UL; // 16 MHz
static const byte MCP2515_INT = 2; // INT output of MCP2515 (adapt to your design)
static const byte MCP2515_CS = 10; // CS input of MCP2515 (adapt to your design)
ACAN2515 can(MCP2515_CS, SPI, MCP2515_INT);
#endif
static const uint32_t DESIRED_BIT_RATE = 250UL * 1000UL; // Marklin CAN baudrate = 250Kbit/s
/* -------------------------------------------------------------------
TrackController (constructor / destructor)
------------------------------------------------------------------- */
TrackController::TrackController()
: mHash(0),
mDebug(false),
mLoopback(false),
mTimeout(1000)
{
if (mDebug)
Serial.println("### Creating controller");
}
TrackController::TrackController(uint64_t timeOut)
: mHash(0),
mDebug(false),
mLoopback(false),
mTimeout(timeOut)
{
if (mDebug)
Serial.println("### Creating controller");
}
TrackController::TrackController(uint16_t hash, bool debug, uint64_t timeOut)
: mHash(hash),
mDebug(debug),
mLoopback(false),
mTimeout(timeOut)
{
if (mDebug)
Serial.println("### Creating controller with param");
}
TrackController::TrackController(uint16_t hash, bool debug, uint64_t timeOut, bool loopback)
: mHash(hash),
mDebug(debug),
mLoopback(loopback),
mTimeout(timeOut)
{
if (mDebug)
Serial.println("### Creating controller with param");
}
TrackController::~TrackController() // Destructeur
{
if (mDebug)
Serial.println("### Destroying controller");
}
/* -------------------------------------------------------------------
TrackController::init
------------------------------------------------------------------- */
// Kept for compatibility with older versions but not used from v-0.9.x
void TrackController::init(uint16_t hash, bool debug, bool loopback, uint64_t timeOut)
{
mHash = hash;
mDebug = debug;
mLoopback = loopback;
mTimeout = timeOut;
}
/* -------------------------------------------------------------------
TrackController::getHash
------------------------------------------------------------------- */
uint16_t TrackController::getHash()
{
return mHash;
}
/* -------------------------------------------------------------------
TrackController::isDebug
------------------------------------------------------------------- */
bool TrackController::isDebug()
{
return mDebug;
}
/* -------------------------------------------------------------------
TrackController::isLoopback
------------------------------------------------------------------- */
bool TrackController::isLoopback()
{
return mLoopback;
}
/* -------------------------------------------------------------------
TrackController::begin
------------------------------------------------------------------- */
void TrackController::begin(const byte can_rx_pin, const byte can_tx_pin)
{
//--- Configure CAN
#if defined ARDUINO_ARCH_ESP32
Serial.println("Configure ESP32 CAN");
ACAN_ESP32_Settings settings(DESIRED_BIT_RATE); // Marklin CAN baudrate = 250Kbit/s
settings.mRxPin = (gpio_num_t)can_rx_pin;
settings.mTxPin = (gpio_num_t)can_tx_pin;
const uint32_t errorCode = ACAN_ESP32::can.begin(settings);
#elif defined ARDUINO_ARCH_AVR
//--- Begin SPI
SPI.begin();
Serial.println("Configure ACAN2515");
ACAN2515Settings settings(QUARTZ_FREQUENCY, DESIRED_BIT_RATE);
const uint16_t errorCode = can.begin(settings, []
{ can.isr(); });
#endif
if (errorCode)
{
Serial.print("Configuration error 0x");
Serial.println(errorCode, HEX);
}
else
{
Serial.print("Bit Rate prescaler: ");
Serial.println(settings.mBitRatePrescaler);
Serial.print("Triple Sampling: ");
Serial.println(settings.mTripleSampling ? "yes" : "no");
Serial.print("Actual bit rate: ");
Serial.print(settings.actualBitRate());
Serial.println(" bit/s");
Serial.print("Exact bit rate ? ");
Serial.println(settings.exactBitRate() ? "yes" : "no");
Serial.print("Sample point: ");
Serial.print(settings.samplePointFromBitStart());
Serial.println("%");
}
Serial.println("Configuration CAN OK");
Serial.println("");
delay(500);
if (!mLoopback)
{
TrackMessage message;
message.clear();
message.prio = 0x00;
message.command = 0x1B;
message.response = false;
message.length = 5;
message.data[4] = 0x11;
sendMessage(message);
}
if (mHash == 0)
generateHash();
}
/* -------------------------------------------------------------------
TrackController::end
------------------------------------------------------------------- */
// void TrackController::end() {
// detachInterrupt(CAN_INT);
// can_t t;
// boolean b = dequeue(&t);
// while (b) {
// b = dequeue(&t);
// }
// }
/* -------------------------------------------------------------------
TrackController::sendMessage
------------------------------------------------------------------- */
bool TrackController::sendMessage(TrackMessage &message)
{
CANMessage frame;
message.hash = mHash;
frame.id = (static_cast<uint32_t>(message.prio) << 25) | (static_cast<uint32_t>(message.command) << 17) | (static_cast<uint32_t>(message.response) << 16) | message.hash;
frame.ext = true;
frame.len = message.length;
for (byte i = 0; i < message.length; i++)
frame.data[i] = message.data[i];
if (mDebug)
{
Serial.print("<== ID : 0x");
Serial.println(frame.id, HEX);
Serial.print("EXT : ");
Serial.println(frame.ext ? "extended" : "standard");
Serial.print("RESP : ");
Serial.println((frame.id & 0x10000) >> 16);
Serial.print("DLC : ");
Serial.println(frame.len);
Serial.print("COMMAND : 0x");
TrackMessage::printHex(Serial, (frame.id & 0x1FE0000) >> 17, 2);
Serial.print("\nDATA : ");
for (uint8_t i = 0; i < frame.len; i++)
{
Serial.print("0x");
TrackMessage::printHex(Serial, frame.data[i], 2);
if (i < frame.len - 1)
Serial.print(" - ");
}
Serial.print("\n------------------------------------------------------------------\n");
}
#if defined(ARDUINO_ARCH_ESP32)
return ACAN_ESP32::can.tryToSend(frame);
#elif defined(ARDUINO_ARCH_AVR)
return can.tryToSend(frame);
#endif
}
/* -------------------------------------------------------------------
TrackController::receiveMessage
------------------------------------------------------------------- */
bool TrackController::receiveMessage(TrackMessage &message)
{
CANMessage frame;
#if defined(ARDUINO_ARCH_ESP32)
bool result = ACAN_ESP32::can.receive(frame);
#elif defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
bool result = can.receive(frame);
#endif
if (result)
{
if (mDebug)
{
Serial.print("==> ID : 0x");
Serial.println(frame.id, HEX);
Serial.print("EXT : ");
Serial.println(frame.ext ? "extended" : "standard");
Serial.print("RESP : ");
Serial.println((frame.id & 0x10000) >> 16);
Serial.print("DLC : ");
Serial.println(frame.len);
Serial.print("COMMAND : 0x");
TrackMessage::printHex(Serial, (frame.id & 0x1FE0000) >> 17, 2);
Serial.print("\nDATA : ");
for (uint8_t i = 0; i < frame.len; i++)
{
Serial.print("0x");
TrackMessage::printHex(Serial, frame.data[i], 2);
if (i < frame.len - 1)
Serial.print(" - ");
}
Serial.print("\n------------------------------------------------------------------\n");
}
message.clear();
message.command = (frame.id >> 17) & 0xFF;
message.hash = frame.id & 0xFFFF;
message.response = (frame.id >> 16) & 0x01;
message.length = frame.len;
for (uint8_t i = 0; i < frame.len; i++)
message.data[i] = frame.data[i];
// if (mDebug) {
// Serial.print("<== 0x");
// Serial.println(frame.id, HEX);
// }
}
return result;
}
/* -------------------------------------------------------------------
TrackController::exchangeMessage
------------------------------------------------------------------- */
bool TrackController::exchangeMessage(TrackMessage &out, TrackMessage &in, uint16_t timeout)
{
uint16_t command = out.command;
if (!sendMessage(out))
{
if (mDebug)
{
Serial.println(F("!!! Send error"));
Serial.println(F("!!! Emergency stop"));
setPower(false);
for (;;)
;
}
}
// uint32_t time = millis();
uint64_t time = millis();
/* -- TrackMessage response -- */
while (millis() < time + timeout)
{
in.clear();
boolean result = receiveMessage(in);
if (result && in.command == command && in.response)
return true;
}
if (mDebug)
Serial.println(F("!!! Receive timeout"));
return false;
}
/* -------------------------------------------------------------------
TrackController::generateHash
------------------------------------------------------------------- */
void TrackController::generateHash()
{
TrackMessage message;
bool ok = false;
while (!ok)
{
mHash = (random(0x10000) & 0xFF7F) | 0x0300;
if (mDebug)
{
Serial.print(F("### Trying new hash 0x"));
message.printHex(Serial, mHash, 4);
Serial.print(F("\n------------------------------------------------------------------\n"));
}
message.clear();
message.command = 0x18; // Ping, demande aux equipements sur le bus
sendMessage(message);
delay(mTimeout);
ok = true;
while (receiveMessage(message))
{
if (message.hash == mHash)
ok = false;
}
}
if (mDebug)
{
Serial.print(F("### New hash looks good"));
Serial.print(F("\n------------------------------------------------------------------\n"));
}
}
/* -------------------------------------------------------------------
TrackController::setPower
------------------------------------------------------------------- */
bool TrackController::setPower(bool power)
{
TrackMessage message;
auto exchange = [this, &message](uint16_t timeout)
{
return exchangeMessage(message, message, timeout);
};
/*
Arrêt du système ou Démarrage du système
Commande système (0x00, dans CAN-ID : 0x00)
Sous-commande dans data[4] = 0: Arrêt du système (0x00)
Sous-commande dans data[4] = 1: Démarrage du système (0x01)
*/
message.clear();
message.prio = 0x00;
message.command = 0x00; // Commande système (0x00, dans CAN-ID : 0x00)
message.response = false; // bit de réponse désactivé.
message.length = 5;
message.data[4] = power ? true : false; // Sous-commande Arrêt ou Démarrage
// /* new version */
if (!exchange(mTimeout))
{
if (mDebug)
{
Serial.println("Failed to send Power");
}
return false;
}
else
{
if (mDebug)
{
Serial.print("Power ");
Serial.print(power ? "on" : "off");
Serial.print("\n------------------------------------------------------------------\n");
}
}
if (power)
{
/*
Réinitialiser le compteur de réenregistrement MFX
Commande système (0x00, dans CAN-ID : 0x00)
Sous-commande : Compteur de réenregistrement (0x09)
*/
message.clear();
message.prio = 0x00;
message.command = 0x00; // Commande système (0x00, dans CAN-ID : 0x00)
message.response = false; // bit de réponse desactivé.
message.length = 7;
message.data[4] = 0x09; // Sous-commande Compteur de réenregistrement
message.data[6] = 0x03; // Réinitialiser le compteur de réenregistrement à 3.
/* old version */
// exchangeMessage(message, message, 1000);
/* new version */
if (!exchange(mTimeout))
{
if (mDebug)
Serial.println("Failed to reset re-registration counter");
return false;
}
/*
Activer ou désactiver le protocole de voie
Commande système (0x00, dans CAN-ID : 0x00)
Sous-commande : • Protocole de voie (0x08)
*/
message.clear();
message.prio = 0x00;
message.command = 0x00; // Commande système (0x00, dans CAN-ID : 0x00)
message.response = false; // bit de réponse desactivé.
message.length = 6;
message.data[4] = 0x08; // Sous-commande protocole de voie
message.data[5] = 0x07; // bit0 = MM2 - bit1 = MFX - bit2 = DCC
/* old version */
// exchangeMessage(message, message, 1000);
/* new version */
if (!exchange(mTimeout))
{
if (mDebug)
Serial.println("Failed to activate track protocol");
return false;
}
}
return true;
}
/* -------------------------------------------------------------------
TrackController::systemHalt
------------------------------------------------------------------- */
bool TrackController::systemHalt(const uint16_t address)
{
TrackMessage message;
message.clear();
message.prio = 0x00;
message.command = 0x00;
message.length = 5;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = 0x02;
return exchangeMessage(message, message, mTimeout);
}
/* -------------------------------------------------------------------
TrackController::emergency
------------------------------------------------------------------- */
bool TrackController::emergency(const uint16_t address)
{
TrackMessage message;
message.clear();
message.prio = 0x00;
message.command = 0x00;
message.length = 5;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = 0x03;
return exchangeMessage(message, message, mTimeout);
}
/* -------------------------------------------------------------------
TrackController::setLocoDirection
------------------------------------------------------------------- */
bool TrackController::setLocoDirection(const uint16_t address, byte direction)
{
TrackMessage message;
/* Sur la MS2, le changement de direction est precede d'un arret d'urgence de la locomotive
Commande systeme 0x00 Sous Commande 0x03
Cet arret d'urgence est remplace ici par une vitesse 0
*/
// message.clear();
// message.command = 0x00;
// message.length = 5;
// message.data[2] = (address & 0xFF00) >> 8;
// message.data[3] = (address & 0x00FF);
// message.data[4] = 0x03;
// message.clear();
// message.command = 0x04; // Commande : LocVitesse
// message.length = 6;
// message.data[2] = (address & 0xFF00) >> 8;
// message.data[3] = (address & 0x00FF);
// message.data[5] = 0;
// return exchangeMessage(message, message, mTimeout);
message.clear();
message.command = 0x05;
message.length = 5;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = direction;
return exchangeMessage(message, message, mTimeout);
}
/* -------------------------------------------------------------------
TrackController::toggleLocoDirection
------------------------------------------------------------------- */
bool TrackController::toggleLocoDirection(const uint16_t address)
{
return setLocoDirection(address, DIR_CHANGE);
}
/* -------------------------------------------------------------------
TrackController::getLocoDirection
------------------------------------------------------------------- */
bool TrackController::getLocoDirection(const uint16_t address, byte *direction)
{
TrackMessage message;
message.clear();
message.command = 0x05;
message.length = 4;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
if (exchangeMessage(message, message, mTimeout))
{
*direction = message.data[4];
return true;
}
else
return false;
}
/* -------------------------------------------------------------------
TrackController::setLocoFunction
------------------------------------------------------------------- */
bool TrackController::setLocoFunction(const uint16_t address, byte function, byte power)
{
TrackMessage message;
message.clear();
message.command = 0x06;
message.length = 6;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = function;
message.data[5] = power;
return exchangeMessage(message, message, mTimeout);
}
/* -------------------------------------------------------------------
TrackController::readConfig
------------------------------------------------------------------- */
bool TrackController::readConfig(const uint16_t address, uint16_t number, byte *value)
{
TrackMessage message;
message.clear();
message.command = 0x07;
message.length = 7;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = highByte(number);
message.data[5] = lowByte(number);
message.data[6] = 0x01;
if (exchangeMessage(message, message, mTimeout))
{
*value = message.data[6];
return true;
}
else
return false;
}
/* -------------------------------------------------------------------
TrackController::getLocoFunction
------------------------------------------------------------------- */
bool TrackController::getLocoFunction(const uint16_t address, byte function, byte *power)
{
TrackMessage message;
message.clear();
message.command = 0x06;
message.length = 5;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = function;
if (exchangeMessage(message, message, mTimeout))
{
*power = message.data[5];
return true;
}
else
return false;
}
/* -------------------------------------------------------------------
TrackController::setLocoSpeed
------------------------------------------------------------------- */
bool TrackController::setLocoSpeed(const uint16_t address, uint16_t speed)
{
TrackMessage message;
message.clear();
message.command = 0x04;
message.length = 6;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = address & 0x00FF;
message.data[4] = (speed & 0xFF00) >> 8;
message.data[5] = speed & 0x00FF;
return exchangeMessage(message, message, mTimeout);
}
/* -------------------------------------------------------------------
TrackController::toggleLocoFunction
------------------------------------------------------------------- */
bool TrackController::toggleLocoFunction(const uint16_t address, byte function)
{
byte power;
if (getLocoFunction(address, function, &power))
{
return setLocoFunction(address, function, power ? 0 : 1);
}
return false;
}
/* -------------------------------------------------------------------
TrackController::setAccessory
------------------------------------------------------------------- */
boolean TrackController::setAccessory(const uint16_t address, byte position, byte power, uint16_t time)
{
TrackMessage message;
message.clear();
message.command = 0x0B;
message.length = 6;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = position;
message.data[5] = power;
exchangeMessage(message, message, mTimeout);
if (time != 0)
{
delay(time);
message.clear();
message.command = 0x0B;
message.length = 6;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = position;
exchangeMessage(message, message, mTimeout);
}
return true;
}
/* -------------------------------------------------------------------
TrackController::setTurnout
------------------------------------------------------------------- */
bool TrackController::setTurnout(const uint16_t address, bool straight)
{
return setAccessory(address, straight ? ACC_STRAIGHT : ACC_ROUND, 1, 1000);
}
/* -------------------------------------------------------------------
TrackController::getLocoSpeed
------------------------------------------------------------------- */
bool TrackController::getLocoSpeed(const uint16_t address, uint16_t *speed)
{
TrackMessage message;
message.clear();
message.command = 0x04;
message.length = 4;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
if (exchangeMessage(message, message, mTimeout))
{
*speed = (message.data[4] << 8) | message.data[5];
return true;
}
else
return false;
}
/* -------------------------------------------------------------------
TrackController::getAccessory
------------------------------------------------------------------- */
bool TrackController::getAccessory(const uint16_t address, byte *position, byte *power)
{
TrackMessage message;
message.clear();
message.command = 0x0B;
message.length = 4;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
if (exchangeMessage(message, message, mTimeout))
{
position[0] = message.data[4];
power[0] = message.data[5];
return true;
}
else
{
return false;
}
}
/* -------------------------------------------------------------------
TrackController::getVersion
------------------------------------------------------------------- */
bool TrackController::getVersion()
{
bool result = false;
TrackMessage message;
message.clear();
message.command = 0x18;
if (exchangeMessage(message, message, mTimeout))
{
Serial.print("version : ");
Serial.print(message.data[4]);
Serial.println(message.data[5]);
return result = true;
}
// sendMessage(message);
// delay(500);
// message.clear();
// while (receiveMessage(message)) {
// if (message.command == 0x18 && message.response) {
// //if (message.command == 0x18 && message.data[6] == 0x00 && message.data[7] == 0x10) {
// // *high = message.data[4];
// // *low = message.data[5];
// Serial.print("version : ");
// Serial.print(message.data[4]);
// Serial.println(message.data[5]);
// result = true;
// }
// }
return result;
}
/* -------------------------------------------------------------------
TrackController::writeConfig
------------------------------------------------------------------- */
bool TrackController::writeConfig(const uint16_t address, uint16_t number, byte value)
{
TrackMessage message;
message.clear();
message.prio = 0x01;
message.command = 0x08;
message.length = 8;
message.data[2] = (address & 0xFF00) >> 8;
message.data[3] = (address & 0x00FF);
message.data[4] = highByte(number);
message.data[5] = lowByte(number);
message.data[6] = value;
return exchangeMessage(message, message, mTimeout);
}
/* -------------------------------------------------------------------
TrackController::handleUserCommands
------------------------------------------------------------------- */
void TrackController::handleUserCommands(String command)
{
if (command.startsWith("power ")) // EX power 1 (on); power 0 (off)
{
bool power = command.substring(6).toInt();
setPower(power);
}
else if (command.startsWith("emergency "))
{
uint16_t address = command.substring(10, 15).toInt();
emergency(address);
}
else if (command.startsWith("direction "))
{
uint16_t address = command.substring(10, 15).toInt();
uint8_t direction = command.substring(16).toInt();
setLocoDirection(address, direction);
}
else if (command.startsWith("speed ")) // Ex speed 16391 100; 16391 = 0x40 | 0x07; 100 = speed/1000
{
uint16_t address = command.substring(6, 11).toInt();
uint16_t speed = command.substring(12).toInt();
setLocoSpeed(address, speed);
}
else if (command.startsWith("function ")) // Ex function 16391 0 1; 16391 = 0x40 | 0x07; 0 = feux; 1 = true
{
uint16_t address = command.substring(9, 14).toInt();
uint8_t function = command.substring(15, 16).toInt();
uint8_t power = command.substring(16).toInt();
setLocoFunction(address, function, power);
}
else if (command.startsWith("accessory "))
{
uint16_t address = command.substring(10, 15).toInt();
uint8_t position = command.substring(16, 17).toInt();
uint8_t power = command.substring(17, 18).toInt();
uint16_t time = command.substring(19).toInt();
setAccessory(address, position, power, time);
}
//}
}

View File

@@ -0,0 +1,349 @@
/*********************************************************************
* Railuino - Hacking your Märklin
*
* Copyright (C) 2012 Joerg Pleumann
* Copyright (C) 2024 christophe bobille
*
* This example is free software; you can redistribute it and/or
* modify it under the terms of the Creative Commons Zero License,
* version 1.0, as published by the Creative Commons Organisation.
* This effectively puts the file into the public domain.
*
* This example is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* LICENSE file for more details.
*/
#ifndef TRACKCONTROLLER_H
#define TRACKCONTROLLER_H
#include <Arduino.h>
#include "TrackMessage.h"
#include "Config.h"
// ===================================================================
// === TrackController ===============================================
// ===================================================================
/**
* Controls things on and connected to the track: locomotives,
* turnouts and other accessories. While there are some low-level
* methods for dealing with messages, you will normally want to use
* the high-level methods that wrap most of the the nasty protocol
* details. When addressing something, you have to tell the system the
* type of address (or decoder) you are using by adding the proper
* protocol base address. For instance, DCC locomotive 42 is properly
* addressed as ADDR_DCC + 42.
*/
class TrackController
{
private:
/**
* Stores the hash of our controller. This must not conflict with
* hashes of other devices in the setup (most likely the MS2 and
* the connector box).
*/
uint16_t mHash;
/**
* Stores the debug flag. When debugging is on, all outgoing and
* incoming messages are printed to the Serial console.
*/
bool mDebug;
/**
* Holds the loopback flag. When loopback is on, messages are
* reflected by the CAN controller. No external communication
* takes place. This is helpful for some test cases.
*/
bool mLoopback;
uint64_t mTimeout;
public:
/**
* Creates a new TrackController with default values.
*/
TrackController();
/**
* Creates a new TrackController with modification of the default exchangeMessage timeout
*/
TrackController(uint64_t timeOut);
/**
* Creates a new TrackController with the given hash and debugging
* flag and changing the default exchangeMessage timeout.
* A zero hash will result in a unique hash begin generated.
*/
TrackController(uint16_t hash, bool debug, uint64_t timeOut);
/**
* Creates a new TrackController with the given hash and debugging
* flag. A zero hash will result in a unique hash begin generated.
*/
TrackController(uint16_t hash, bool debug, uint64_t timeOut, bool loopback);
/**
* Is called when a TrackController is being destroyed. Does the
* necessary cleanup. No need to call this manually.
*/
~TrackController();
/**
* Initializes the TrackController with the given values. This
* should be called before begin, otherwise it will not take
* effect. A zero hash will result in a unique hash begin
* generated.
*/
void init(uint16_t hash, bool debug, bool loopback, uint64_t timeOut = 1000);
/**
* Queries the hash used by the TrackController.
*/
uint16_t getHash();
/**
* Reflects whether the TrackController is in debug mode,
* where all messages are dumped to the Serial console.
*/
bool isDebug();
/**
* Reflects whether the TrackController is in debug mode,
* where all messages are reflected by the CAN controller.
*/
bool isLoopback();
/**
* Initializes the CAN hardware and starts receiving CAN
* messages. CAN messages are put into an internal buffer of
* limited size, so they don't get lost, but you have to take
* care of them in time. Otherwise the buffer might overflow.
* default CAN Rx pin is GPIO_NUM_5 and can_tx_pin is GPIO_NUM_4
*/
// void begin(const gpio_num_t can_rx_pin = GPIO_NUM_5,
// const gpio_num_t can_tx_pin = GPIO_NUM_4);
void begin(const byte can_rx_pin = 5,
const byte can_tx_pin = 4);
/**
* Generates a new hash and makes sure it does not conflict
* with those of other devices in the setup.
*/
void generateHash();
/**
* Stops receiving messages from the CAN hardware. Clears
* the internal buffer.
*/
// void end();
/**
* Sends a message and reports true on success. Internal method.
* Normally you don't want to use this, but the more convenient
* methods below instead.
*/
bool sendMessage(TrackMessage &message);
/**
* Receives an arbitrary message, if available, and reports true
* on success. Does not block. Internal method. Normally you
* don't want to use this, but the more convenient methods below
* instead.
*/
bool receiveMessage(TrackMessage &message);
/**
* Sends a message and waits for the corresponding response,
* returning true on success. Blocks until either a message with
* the same command ID and the response marker arrives or the
* timeout (in ms) expires. All non-matching messages are
* skipped. Internal method. Normally you don't want to use this,
* but the more convenient methods below instead. 'out' and 'in'
* may be the same object.
*/
bool exchangeMessage(TrackMessage &out, TrackMessage &in, uint16_t timeout);
/**
* Controls power on the track. When passing false, all
* locomotives will stop, but remember their previous directions
* and speeds. When passing true, all locomotives will regain
* their old directions and speeds. The system starts in
* stopped mode in order to avoid accidents. The return value
* reflects whether the call was successful.
*/
bool setPower(bool power);
/**
* Cette commande qui n'existait pas a l'origine a ete ajoutee
* a partir de la v-9.01
* Commande système (0x00, dans CAN-ID : 0x00)
* Arrêt d'urgence de la locomotive (0x02)
* Toutes les locomotives reçoivent l'ordre de s'arrêter (vitesse 0),
* y compris l'inertie de freinage. Le signal numérique reste sur les rails,
* mais aucune autre commande n'est envoyée sur les rails.
* L'énergie électrique reste disponible.
*/
// See https://streaming.maerklin.de/public-media/cs2/cs2CAN-Protokoll-2_0.pdf -> 2.3 Commande : System Halt
bool systemHalt(const uint16_t address);
/**
* Cette commande qui n'existait pas a l'origine a ete ajoutee
* a partir de la v-9.01
* Commande système (0x00, dans CAN-ID : 0x00)
* Arrêt d'urgence de la locomotive (0x03)
* Arrêt d'urgence ou arrêt immédiat de la locomotive, selon le protocole de voie.
* Il faut spécifier une locomotive déjà ciblée par une commande.
* Si cette locomotive n'est pas déjà dans le cycle, elle ne sera pas prise en compte par cette commande.
*/
/**
* This command, which didn't exist originally, has been added from v-9.01
* System command (0x00, in CAN-ID: 0x00)
* Locomotive emergency stop (0x03)
* Emergency stop or immediate stop of locomotive, depending on track protocol.
* A locomotive already targeted by a command must be specified.
* If this locomotive is not already in the cycle, it will not be taken into account by this command.
*/
// See https://streaming.maerklin.de/public-media/cs2/cs2CAN-Protokoll-2_0.pdf -> 2.4 Commande : Arrêt d'urgence de la locomotive
bool emergency(const uint16_t address);
/**
* Sets the direction of the given locomotive. Valid directions
* are those specified by the DIR_* constants. The return value
* reflects whether the call was successful.
*/
bool setLocoDirection(const uint16_t address, uint8_t direction);
/**
* Toggles the direction of the given locomotive. This normally
* includes a full stop.
*/
bool toggleLocoDirection(const uint16_t address);
/**
* Sets the speed of the given locomotive. Valid speeds are
* 0 to 1023 (inclusive), though the connector box will limit
* all speeds beyond 1000 to 1000. The return value reflects
* whether the call was successful.
*/
bool setLocoSpeed(const uint16_t address, uint16_t speed);
// bool accelerateLoco(uint16_t address);
// bool decelerateLoco(uint16_t address);
/**
* Sets the given function of the given locomotive (or simply a
* function decoder). Valid functions are 0 to 31, with 0
* normally denoting the head/backlight. Valid values are, again,
* 0 ("off") to 31, although not all protocols support values
* beyond 1 (which then means "on"). The return value reflects
* whether the call was successful.
*/
bool setLocoFunction(const uint16_t address, uint8_t function, uint8_t power);
/**
* Toggles the given function of the given locomotive. Valid
* functions are 0 to 31, with 0 normally denoting the
* head/backlight.
*/
bool toggleLocoFunction(const uint16_t address, uint8_t function);
/**
* Switches the given magnetic accessory. Valid position values
* are those denoted by the ACC_* constants. Valid power values
* are 0 ("off") to 31 (inclusive) although not all protocols
* support values beyond 1 (which then means "on"). The final
* parameter specifies the time (in ms) for which the accessory
* will be active. A time of 0 means the accessory will only be
* switched on. Some magnetic accessories must not be active for
* too long, because they might burn out. A good timeout for
* Marklin turnouts seems to be 20 ms. The return value reflects
* whether the call was successful.
*/
bool setAccessory(const uint16_t address, uint8_t position, uint8_t power, uint16_t time);
/**
* Switches a turnout. This is actually a convenience function
* around setAccessory() that uses default values for some
* parameters. The return value reflects whether the call was
* successful.
*/
bool setTurnout(const uint16_t address, bool straight);
/**
* Queries the direction of the given locomotive and writes it
* into the referenced byte. The return value indicates whether
* the call was successful and the direction is valid.
*/
bool getLocoDirection(const uint16_t address, uint8_t *direction);
/**
* Queries the speed of the given locomotive and writes it
* into the referenced byte. The return value indicates whether
* the call was successful and the speed is valid.
*/
bool getLocoSpeed(const uint16_t address, uint16_t *speed);
/**
* Queries the given function of the given locomotive and writes
* it into the referenced byte. The return value indicates
* whether the call was successful and the power is valid. Note
* that the call will not reflect the original power value sent
* to the function, but only 0 ("off") or 1 ("on").
*/
bool getLocoFunction(const uint16_t address, uint8_t function, uint8_t *power);
/**
* Queries the given magnetic accessory's state and and writes
* it into the referenced bytes. The return value indicates
* whether the call was successful and the bytes are valid. Note
* that the call will not reflect the original power value sent
* to the function, but only 0 ("off") or 1 ("on").
*/
bool getAccessory(const uint16_t address, uint8_t *position, uint8_t *power);
/**
* Writes the given value to the given config number of the given
* locomotive. The return value reflects whether the call was
* successful.
*/
/* -------------------------------------------------------------------
TrackController::writeConfig
See https://streaming.maerklin.de/public-media/cs2/cs2CAN-Protokoll-2_0.pdf -> 3.8 Commande : Écrire Config
------------------------------------------------------------------- */
bool writeConfig(const uint16_t address, uint16_t number, uint8_t value);
/**
* Reads the given config number of the given locomotive into the
* given value.
*/
//!\\ Les décodeurs MFX de première génération ne sont pas conçus pour cela et pourraient être endommagés
//!\\ First-generation MFX decoders are not designed for this purpose and could be damaged.
// See https://streaming.maerklin.de/public-media/cs2/cs2CAN-Protokoll-2_0.pdf -> 2.8 Befehl: Fast Read für mfx SID - Adresse
bool readConfig(const uint16_t address, uint16_t number, uint8_t *value);
/**
* Queries the software version of the track format processor.
*/
bool getVersion();
//bool getVersion(uint8_t *high, uint8_t *low);
/**
* Processes commands received on the serial or TCP port
*/
void handleUserCommands(String);
};
#endif // TRACKCONTROLLER_H

View File

@@ -0,0 +1,123 @@
/*********************************************************************
* Railuino - Hacking your Märklin
*
* Copyright (C) 2012 Joerg Pleumann
* Copyright (C) 2024 christophe bobille
*
* This example is free software; you can redistribute it and/or
* modify it under the terms of the Creative Commons Zero License,
* version 1.0, as published by the Creative Commons Organisation.
* This effectively puts the file into the public domain.
*
* This example is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* LICENSE file for more details.
*/
#include "TrackMessage.h"
/* -------------------------------------------------------------------
TrackMessage::printHex
------------------------------------------------------------------- */
size_t TrackMessage::printHex(Print &p, uint32_t hex, uint16_t digits)
{
size_t size = 0;
String s = String(hex, HEX);
for (uint16_t i = s.length(); i < digits; i++)
size += p.print("0");
size += p.print(s);
return size;
}
/* -------------------------------------------------------------------
TrackMessage::parseHex
------------------------------------------------------------------- */
uint8_t TrackMessage::parseHex(String &s, uint8_t start, uint8_t end, bool *ok)
{
uint8_t value = 0;
for (uint8_t i = start; i < end; i++)
{
char c = s.charAt(i);
if (c >= '0' && c <= '9')
value = 16 * value + c - '0';
else if (c >= 'a' && c <= 'f')
value = 16 * value + 10 + c - 'a';
else if (c >= 'A' && c <= 'F')
value = 16 * value + 10 + c - 'A';
else
{
*ok = false;
return -1;
}
}
return value;
}
/* -------------------------------------------------------------------
TrackMessage::clear
------------------------------------------------------------------- */
void TrackMessage::clear()
{
prio = 0;
command = 0;
hash = 0;
response = false;
length = 0;
memset(data, 0x00, 8);
}
/* -------------------------------------------------------------------
TrackMessage::printTo
------------------------------------------------------------------- */
size_t TrackMessage::printTo(Print &p) const
{
size_t size = 0;
size += printHex(p, hash, 4);
size += p.print(response ? " R " : " ");
size += printHex(p, command, 2);
size += p.print(" ");
size += printHex(p, length, 1);
for (int i = 0; i < length; i++)
{
size += p.print(" ");
size += printHex(p, data[i], 2);
}
return size;
}
/* -------------------------------------------------------------------
TrackMessage::parseFrom
------------------------------------------------------------------- */
bool TrackMessage::parseFrom(String &s)
{
bool result = true;
clear();
if (s.length() < 11)
return false;
hash = parseHex(s, 0, 4, &result);
response = s.charAt(5) != ' ';
command = parseHex(s, 7, 9, &result);
length = parseHex(s, 10, 11, &result);
if (length > 8)
return false;
if (s.length() < static_cast<size_t>(11) + 3 * length)
return false;
for (int i = 0; i < length; i++)
data[i] = parseHex(s, 12 + 3 * i, 12 + 3 * i + 2, &result);
return result;
}

View File

@@ -0,0 +1,91 @@
/*********************************************************************
* Railuino - Hacking your Märklin
*
* Copyright (C) 2012 Joerg Pleumann
* Copyright (C) 2024 christophe bobille
*
* This example is free software; you can redistribute it and/or
* modify it under the terms of the Creative Commons Zero License,
* version 1.0, as published by the Creative Commons Organisation.
* This effectively puts the file into the public domain.
*
* This example is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* LICENSE file for more details.
*/
#ifndef TRACKCMESSAGE_H
#define TRACKCMESSAGE_H
#include <Arduino.h>
/**
* Represents a message going through the Marklin CAN bus. More or
* less a beautified version of the real CAN message. You normally
* don't need to use this unless you want to experiment with the
* protocol or extend the library. See the Marklin protocol
* documentation for details. The TrackMessage is a Printable, so
* it can be directly used in Serial.println(), for instance. It
* can also be converted from a String.
*/
class TrackMessage
{
private:
public:
/**
* The priority number.
*/
uint8_t prio;
/**
* The command number.
*/
uint8_t command;
/**
* Whether this is a response to a request.
*/
bool response;
/**
* The hash that is used for avoiding device/message collisions.
*/
uint16_t hash;
/**
* The number of data bytes in the payload.
*/
uint8_t length;
/**
* The actual message data bytes.
*/
uint8_t data[8];
/**
* Clears the message, setting all values to zero. Provides for
* easy recycling of TrackMessage objects.
*/
void clear();
/**
* Prints the message to the given Print object, which could be a
* Serial object, for instance. The message format looks like this
*
* HHHH R CC L DD DD DD DD DD DD DD DD
*
* with all numbers being hexadecimals and the data bytes being
* optional beyond what the message length specifies. Exactly one
* whitespace is inserted between different fields as a separator.
*/
size_t printTo(Print &p) const;
/**
* Parses the message from the given String. Returns true on
* success, false otherwise. The message must have exactly the
* format that printTo creates. This includes each and every
* whitespace. If the parsing fails the state of the object is
* undefined afterwards, and a clear() is recommended.
*/
bool parseFrom(String &s);
static size_t printHex(Print &p, uint32_t hex, uint16_t digits);
static uint8_t parseHex(String &s, uint8_t start, uint8_t end, bool *ok);
};
#endif // TRACKCMESSAGE_H

View File

View File

272
Railuino/src/main.cpp Normal file
View File

@@ -0,0 +1,272 @@
#include <WiFi.h>
#include <WebServer.h>
#include <SPIFFS.h>
#include "Config.h"
#include "TrackController.h"
#include <ACAN_ESP32.h>
bool powerState = false; // Variable globale pour suivre l'état de l'alimentation
const bool DEBUG = true;
byte cBuffer[13];
byte sBuffer[13];
TrackController ctrl(0xDF24, DEBUG);
const char *ssid = "**********";
const char *password = "**********";
IPAddress ip(192, 168, 1, 103);
IPAddress gateway(192, 168, 1, 254);
IPAddress subnet(255, 255, 255, 0);
const uint port = 80;
WebServer server(port);
void handleRoot()
{
File file = SPIFFS.open("/index.html", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "text/html");
file.close();
}
void handleCss()
{
File file = SPIFFS.open("/style.css", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "text/css");
file.close();
}
void handleJs()
{
File file = SPIFFS.open("/script.js", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "text/javascript");
file.close();
}
void handleImage1()
{
File file = SPIFFS.open("/image1.jpg", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "image/jpg");
file.close();
}
void handleImage2()
{
File file = SPIFFS.open("/image2.jpg", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "image/jpg");
file.close();
}
void handleImage3()
{
File file = SPIFFS.open("/image3.jpg", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "image/jpg");
file.close();
}
void handleImage4()
{
File file = SPIFFS.open("/image4.jpg", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "image/jpg");
file.close();
}
void handleFavinco()
{
File file = SPIFFS.open("/favicon.ico", "r");
if (!file)
{
server.send(500, "text/plain", "File not found");
return;
}
size_t sent = server.streamFile(file, "image/x-icon");
file.close();
}
void handleSetPower()
{
auto togglePower = [&]() -> bool
{
powerState = !powerState;
return ctrl.setPower(powerState);
};
if (togglePower())
{
if (powerState)
server.send(200, "text/plain", "true");
else
server.send(200, "text/plain", "false");
}
else
server.send(200, "text/plain", "Error power function");
}
void handleSetStop()
{
if (server.hasArg("address"))
{
uint16_t address = server.arg("address").toInt();
const bool ok = ctrl.setLocoSpeed(address, 0);
if (ok)
server.send(200, "text/plain", "Stop");
else
server.send(400, "text/plain", "Server error");
}
}
void handleSetSystemHalt()
{
if (server.hasArg("address"))
{
uint16_t address = server.arg("address").toInt();
const bool ok = ctrl.systemHalt(address);
if (ok)
server.send(200, "text/plain", "SystemHalt");
else
server.send(200, "text/plain", " Server erro#");
}
else
server.send(400, "text/plain", "Address parameter missing");
}
void handleSetDirection()
{
if (server.hasArg("address"))
{
uint16_t address = server.arg("address").toInt();
ctrl.toggleLocoDirection(address);
server.send(200, "text/plain", "Direction toggled");
}
else
server.send(400, "text/plain", "Address parameter missing");
}
void handleSetSpeed()
{
uint16_t address = 0;
uint16_t speed = 0;
if (server.hasArg("address") && server.hasArg("speed"))
{
address = server.arg("address").toInt();
speed = server.arg("speed").toInt();
ctrl.setLocoSpeed(address, speed);
server.send(200, "text/plain", "Speed set");
}
else
server.send(400, "text/plain", "Speed parameter missing");
}
void handleSetAddress()
{
if (server.hasArg("address"))
{
uint16_t address = server.arg("address").toInt();
server.send(200, "text/plain", "Address set");
}
else
server.send(400, "text/plain", "Address parameter missing");
}
void handleSetFunction()
{
if (server.hasArg("address") && server.hasArg("function") && server.hasArg("power"))
{
uint16_t address = server.arg("address").toInt();
uint8_t function = server.arg("function").toInt();
uint8_t power = server.arg("power").toInt();
ctrl.setLocoFunction(address, function, power);
server.send(200, "text/plain", "Function set");
}
else
server.send(400, "text/plain", "Function parameter missing");
}
void handleNotFound()
{
server.send(404, "text/plain", "Not found");
}
void setup()
{
Serial.begin(115200);
if (!SPIFFS.begin(true))
{
Serial.print("An error has occurred while mounting SPIFFS\n");
return;
}
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED)
{
delay(500);
Serial.print(".");
}
Serial.println("");
Serial.println("WiFi connected.");
Serial.println("IP address: ");
Serial.println(WiFi.localIP());
server.on("/", handleRoot);
server.on("/style.css", handleCss);
server.on("/script.js", handleJs);
server.on("/image1.jpg", handleImage1);
server.on("/image2.jpg", handleImage2);
server.on("/image3.jpg", handleImage3);
server.on("/image4.jpg", handleImage4);
server.on("/favicon.ico", handleFavinco);
server.on("/setPower", HTTP_POST, handleSetPower);
server.on("/setStop", HTTP_POST, handleSetStop);
server.on("/setSystemHalt", HTTP_POST, handleSetSystemHalt);
server.on("/setDirection", HTTP_POST, handleSetDirection);
server.on("/setSpeed", HTTP_POST, handleSetSpeed);
server.on("/setAddress", HTTP_POST, handleSetAddress);
server.on("/setFunction", HTTP_POST, handleSetFunction);
server.onNotFound(handleNotFound);
server.begin();
ctrl.begin();
}
void loop()
{
server.handleClient();
}