Update
This commit is contained in:
BIN
Railuino/.DS_Store
vendored
Normal file
BIN
Railuino/.DS_Store
vendored
Normal file
Binary file not shown.
2
Railuino/.gitattributes
vendored
Normal file
2
Railuino/.gitattributes
vendored
Normal file
@@ -0,0 +1,2 @@
|
||||
# Auto detect text files and perform LF normalization
|
||||
* text=auto
|
||||
5
Railuino/.gitignore
vendored
Normal file
5
Railuino/.gitignore
vendored
Normal file
@@ -0,0 +1,5 @@
|
||||
.pio
|
||||
.vscode/.browse.c_cpp.db*
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
||||
10
Railuino/.vscode/extensions.json
vendored
Normal file
10
Railuino/.vscode/extensions.json
vendored
Normal file
@@ -0,0 +1,10 @@
|
||||
{
|
||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||
// for the documentation about the extensions.json format
|
||||
"recommendations": [
|
||||
"platformio.platformio-ide"
|
||||
],
|
||||
"unwantedRecommendations": [
|
||||
"ms-vscode.cpptools-extension-pack"
|
||||
]
|
||||
}
|
||||
140
Railuino/README.md
Normal file
140
Railuino/README.md
Normal file
@@ -0,0 +1,140 @@
|
||||
# Railuino
|
||||
Rewrite of version 0.9.0 of Joerg Pleumann's Railuino library
|
||||
|
||||
https://youtu.be/x5fVPsChlIA
|
||||
|
||||
Version 0.9.1 de la bibliothèque Railuino de Joerg Pleumann dont le dépôt git se trouve à cet emplacement : https://code.google.com/archive/p/railuino/
|
||||
|
||||
Cette bibliothèque est sous licence GNU LESSER GENERAL PUBLIC LICENSE - Version 2.1, February 1999
|
||||
|
||||
Copyright (C) 2012 Joerg Pleumann
|
||||
|
||||
Cette version 9.0.1 est une réécriture profonde à partir de la version 0.9.0, dernière version publiée à ma connaissance.
|
||||
|
||||
Dans sa version 0.9.0, cette bibliothèque est très bien écrite mais elle est ancienne (2013, c’est beaucoup en programmation), elle n’est pas adaptée aux nouveaux microcontrôleurs comme l’ESP32, comporte quelques manques (comme la reconnaissance automatique en MFX) et doit être optimisée par rapport aux normes C++ 11 et suivantes. Je suis actuellement en train de réécrire certaines parties de cette bibliothèque que je teste au fur et à mesure.
|
||||
|
||||
Je ne m’intéresse actuellement qu’à la version ESP32. Je publie mon travail sur ce git à chaque évolution majeure.
|
||||
|
||||
Les exemples originaux pour la mise en œuvre et les tests de cette bibliothèque sont encore d’actualité mais doivent aussi être adaptés.
|
||||
|
||||
Vous trouverez dans le dossier « exemples » les fichiers mis à jour qui portent les noms originaux auxquels j’ai ajouté « _new ».
|
||||
|
||||
Les fichiers originaux sont conservés à titre de mémoire et de comparaison.
|
||||
|
||||
*****************************************************************************************************
|
||||
|
||||
Version 0.9.1 of Joerg Pleumann's Railuino library, the git repository for which can be found at: https://code.google.com/archive/p/railuino/
|
||||
|
||||
This library is licensed under the GNU LESSER GENERAL PUBLIC LICENSE - Version 2.1, February 1999
|
||||
|
||||
Copyright (C) 2012 Joerg Pleumann
|
||||
|
||||
This version 9.0.1 is a thorough rewrite of version 0.9.0, the last version published to my knowledge.
|
||||
|
||||
In its version 0.9.0, this library is very well written but it is old (2013 is a long time in programming), it is not adapted to new microcontrollers such as the ESP32, has a few shortcomings (such as automatic recognition in MFX) and needs to be optimised in relation to the C++ 11 and later standards. I'm currently rewriting parts of this library and testing them as I go along.
|
||||
|
||||
I'm currently only interested in the ESP32 version. I publish my work on this git whenever there is a major change.
|
||||
|
||||
The original examples for implementing and testing this library are still relevant, but they also need to be adapted.
|
||||
|
||||
You'll find the updated files in the "examples" folder, which have the original names to which I've added "_new".
|
||||
|
||||
The original files are kept for memory and comparison.
|
||||
|
||||
|
||||
|
||||
|
||||
TrackController Class Documentation
|
||||
Overview
|
||||
|
||||
The TrackController class abstracts the communication with Märklin model train components using a CAN bus interface. It provides high-level methods for controlling locomotives, turnouts, and accessories, while managing low-level message handling internally. This documentation summarizes the class's functionality and usage patterns for interfacing with model train systems.
|
||||
|
||||
Dependencies
|
||||
Arduino.h: Arduino standard library.
|
||||
TrackMessage.h: Header for defining CAN message structure.
|
||||
Config.h: Configuration file (not provided) for specific settings.
|
||||
|
||||
Constructors
|
||||
TrackController();
|
||||
Default constructor initializes the controller with default settings.
|
||||
TrackController(uint16_t hash, bool debug);
|
||||
Constructor with parameters to initialize the controller with a specific hash and debug mode.
|
||||
Destructor
|
||||
~TrackController();
|
||||
Cleans up resources when the object is destroyed.
|
||||
|
||||
Public Methods
|
||||
Initialization and Configuration
|
||||
void init(uint16_t hash, bool debug, bool loopback);
|
||||
|
||||
Initializes the controller with a specified hash, debug mode, and loopback mode.
|
||||
void begin();
|
||||
|
||||
Initializes the CAN hardware and starts message reception.
|
||||
void end();
|
||||
|
||||
Stops message reception and clears the internal message buffer.
|
||||
void generateHash();
|
||||
|
||||
Generates a unique hash for the controller to avoid conflicts on the CAN bus.
|
||||
Power and Control
|
||||
bool setPower(bool power);
|
||||
|
||||
Controls the power state of the track. Stops all locomotives when power is false.
|
||||
bool setLocoDirection(uint16_t address, uint8_t direction);
|
||||
|
||||
Sets the direction of a locomotive identified by address.
|
||||
bool toggleLocoDirection(uint16_t address);
|
||||
|
||||
Toggles the direction of a locomotive identified by address.
|
||||
bool setLocoSpeed(uint16_t address, uint16_t speed);
|
||||
|
||||
Sets the speed of a locomotive identified by address.
|
||||
bool setLocoFunction(uint16_t address, uint8_t function, uint8_t power);
|
||||
|
||||
Sets a specific function (e.g., lights) of a locomotive.
|
||||
bool toggleLocoFunction(uint16_t address, uint8_t function);
|
||||
|
||||
Toggles a function (on/off) of a locomotive.
|
||||
bool setAccessory(uint16_t address, uint8_t position, uint8_t power, uint16_t time);
|
||||
|
||||
Controls a magnetic accessory (e.g., turnout).
|
||||
bool setTurnout(uint16_t address, bool straight);
|
||||
|
||||
Controls a turnout to be straight or curved.
|
||||
Query Methods
|
||||
bool getLocoDirection(uint16_t address, uint8_t *direction);
|
||||
|
||||
Queries the direction of a locomotive identified by address.
|
||||
bool getLocoSpeed(uint16_t address, uint16_t *speed);
|
||||
|
||||
Queries the speed of a locomotive identified by address.
|
||||
bool getLocoFunction(uint16_t address, uint8_t function, uint8_t *power);
|
||||
|
||||
Queries the status of a specific function of a locomotive.
|
||||
bool getAccessory(uint16_t address, uint8_t *position, uint8_t *power);
|
||||
|
||||
Queries the state of a magnetic accessory.
|
||||
Configuration Methods
|
||||
bool writeConfig(uint16_t address, uint16_t number, uint8_t value);
|
||||
|
||||
Writes a configuration value to a locomotive.
|
||||
bool readConfig(uint16_t address, uint16_t number, uint8_t *value);
|
||||
|
||||
Reads a configuration value from a locomotive.
|
||||
Utility Methods
|
||||
bool exchangeMessage(TrackMessage &out, TrackMessage &in, uint16_t timeout);
|
||||
|
||||
Sends a message and waits for a response within the specified timeout.
|
||||
bool getVersion(uint8_t *high, uint8_t *low);
|
||||
|
||||
Queries the software version of the track format processor.
|
||||
|
||||
Member Variables
|
||||
uint16_t mHash: Hash of the controller instance.
|
||||
bool mDebug: Debug mode flag.
|
||||
bool mLoopback: Loopback mode flag.
|
||||
|
||||
|
||||
|
||||
|
||||
BIN
Railuino/data/favicon.ico
Normal file
BIN
Railuino/data/favicon.ico
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 1.4 KiB |
BIN
Railuino/data/image1.jpg
Normal file
BIN
Railuino/data/image1.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 7.4 KiB |
BIN
Railuino/data/image2.jpg
Normal file
BIN
Railuino/data/image2.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 3.4 KiB |
BIN
Railuino/data/image3.jpg
Normal file
BIN
Railuino/data/image3.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 2.6 KiB |
BIN
Railuino/data/image4.jpg
Normal file
BIN
Railuino/data/image4.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 4.4 KiB |
48
Railuino/data/index.html
Normal file
48
Railuino/data/index.html
Normal file
@@ -0,0 +1,48 @@
|
||||
<!DOCTYPE html>
|
||||
<html lang="en">
|
||||
<head>
|
||||
<meta charset="UTF-8">
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||
<title>Track Controller</title>
|
||||
<link rel="stylesheet" href="style.css">
|
||||
<link rel="icon" href="favicon.ico" type="image/x-icon">
|
||||
</head>
|
||||
<body>
|
||||
<h1>Track Controller</h1>
|
||||
<div id="logWindow" class="log-window"></div>
|
||||
<div class="image-buttons">
|
||||
<img src="image1.jpg" class="address-button" data-address="16391">
|
||||
<img src="image2.jpg" class="address-button" data-address="11000">
|
||||
<img src="image3.jpg" class="address-button" data-address="12000">
|
||||
<img src="image4.jpg" class="address-button" data-address="13000">
|
||||
</div>
|
||||
<button id="powerButton" class="toggle-button">Power</button>
|
||||
<button id="stopButton" class="normal-button">Stop</button>
|
||||
<button id="systemHaltButton" class="normal-button">System Halt</button>
|
||||
<button id="directionButton" class="toggle-button"><< / >></button>
|
||||
<div class="slider-container">
|
||||
<span class="slider-label" id="slider-min">0</span>
|
||||
<input type="range" id="speedSlider" min="0" max="1000" value="0">
|
||||
<span class="slider-label" id="slider-max">1000</span>
|
||||
</div>
|
||||
<div class="speed-percentage">
|
||||
Speed: <span id="speedValue">0</span>%
|
||||
</div>
|
||||
<div class="function-buttons">
|
||||
<button class="function-button" data-function="0">F0</button>
|
||||
<button class="function-button" data-function="1">F1</button>
|
||||
<button class="function-button" data-function="2">F2</button>
|
||||
<button class="function-button" data-function="3">F3</button>
|
||||
<button class="function-button" data-function="4">F4</button>
|
||||
</div>
|
||||
<div class="function-buttons">
|
||||
<button class="function-button" data-function="5">F5</button>
|
||||
<button class="function-button" data-function="6">F6</button>
|
||||
<button class="function-button" data-function="7">F7</button>
|
||||
<button class="function-button" data-function="8">F8</button>
|
||||
<button class="function-button" data-function="9">F9</button>
|
||||
</div>
|
||||
|
||||
<script src="script.js"></script>
|
||||
</body>
|
||||
</html>
|
||||
180
Railuino/data/script.js
Normal file
180
Railuino/data/script.js
Normal file
@@ -0,0 +1,180 @@
|
||||
let isPowerOn = false;
|
||||
const locos = {};
|
||||
let selectedLoco = null;
|
||||
|
||||
// Classe Loco
|
||||
class Loco {
|
||||
constructor(address) {
|
||||
this.address = address;
|
||||
this.speed = 0;
|
||||
this.direction = 0;
|
||||
this.functions = Array(10).fill(false);
|
||||
}
|
||||
|
||||
setSpeed(speed) {
|
||||
this.speed = speed;
|
||||
}
|
||||
|
||||
setDirection(direction) {
|
||||
this.direction = direction;
|
||||
}
|
||||
|
||||
setFunction(index, state) {
|
||||
this.functions[index] = state;
|
||||
}
|
||||
}
|
||||
|
||||
// Créer des instances de Loco pour chaque bouton image
|
||||
document.querySelectorAll('.address-button').forEach(button => {
|
||||
const address = button.getAttribute('data-address');
|
||||
locos[address] = new Loco(address);
|
||||
});
|
||||
|
||||
// Fonction pour mettre à jour l'affichage avec les valeurs de la locomotive sélectionnée
|
||||
function updateUI() {
|
||||
if (selectedLoco) {
|
||||
document.getElementById('speedSlider').value = selectedLoco.speed;
|
||||
updateSpeedValue(selectedLoco.speed);
|
||||
document.querySelectorAll('.function-button').forEach((button, index) => {
|
||||
if (selectedLoco.functions[index]) {
|
||||
button.classList.add('active');
|
||||
} else {
|
||||
button.classList.remove('active');
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
// Fonction pour ajouter un message au log
|
||||
// function addLogMessage(message) {
|
||||
// const logWindow = document.getElementById('logWindow');
|
||||
// const newMessage = document.createElement('div');
|
||||
// newMessage.textContent = message;
|
||||
// logWindow.appendChild(newMessage);
|
||||
// logWindow.scrollTop = logWindow.scrollHeight;
|
||||
// }
|
||||
|
||||
function addLogMessage(message) {
|
||||
const logWindow = document.getElementById('logWindow');
|
||||
logWindow.textContent = message; // Remplace le contenu du log par le nouveau message
|
||||
}
|
||||
|
||||
// Gestionnaire d'événement pour le bouton d'alimentation
|
||||
document.getElementById('powerButton').addEventListener('click', () => {
|
||||
fetch('/setPower', { method: 'POST' })
|
||||
.then(response => response.text())
|
||||
.then(state => {
|
||||
isPowerOn = state === 'true';
|
||||
const powerButton = document.getElementById('powerButton');
|
||||
if (isPowerOn == true) {
|
||||
powerButton.classList.remove('power-off');
|
||||
powerButton.classList.add('power-on');
|
||||
addLogMessage('Power ON');
|
||||
} else if (isPowerOn == false) {
|
||||
powerButton.classList.remove('power-on');
|
||||
powerButton.classList.add('power-off');
|
||||
addLogMessage('Power OFF');
|
||||
} else {
|
||||
addLogMessage('Error for power function');
|
||||
}
|
||||
});
|
||||
});
|
||||
|
||||
document.getElementById('systemHaltButton').addEventListener('click', () => {
|
||||
if (selectedLoco) {
|
||||
fetch(`/setSystemHalt?address=0x0000`, { method: 'POST' })
|
||||
.then(() => {
|
||||
document.getElementById('speedSlider').value = 0;
|
||||
updateSpeedValue(0);
|
||||
selectedLoco.setSpeed(0);
|
||||
addLogMessage(`System Halt`);
|
||||
});
|
||||
}
|
||||
});
|
||||
|
||||
document.getElementById('stopButton').addEventListener('click', () => {
|
||||
if (selectedLoco) {
|
||||
fetch(`/setStop?address=${selectedLoco.address}`, { method: 'POST' })
|
||||
.then(() => {
|
||||
document.getElementById('speedSlider').value = 0;
|
||||
updateSpeedValue(0);
|
||||
selectedLoco.setSpeed(0);
|
||||
addLogMessage(`Stop for address ${selectedLoco.address}`);
|
||||
});
|
||||
}
|
||||
});
|
||||
|
||||
document.getElementById('directionButton').addEventListener('click', () => {
|
||||
if (selectedLoco) {
|
||||
selectedLoco.direction = 1 - selectedLoco.direction; // Change de direction
|
||||
fetch(`/setDirection?address=${selectedLoco.address}`, { method: 'POST' })
|
||||
.then(() => {
|
||||
document.getElementById('speedSlider').value = 0;
|
||||
updateSpeedValue(0);
|
||||
addLogMessage(`Direction change for address ${selectedLoco.address}`);
|
||||
});
|
||||
}
|
||||
});
|
||||
|
||||
document.getElementById('speedSlider').addEventListener('input', (event) => {
|
||||
if (!isPowerOn) {
|
||||
addLogMessage('Power is off');
|
||||
event.target.value = 0; // Réinitialiser le curseur à 0
|
||||
updateSpeedValue(0);
|
||||
return;
|
||||
}
|
||||
if (!selectedLoco) {
|
||||
addLogMessage('Select a locomotive');
|
||||
event.target.value = 0; // Réinitialiser le curseur à 0
|
||||
updateSpeedValue(0);
|
||||
return;
|
||||
}
|
||||
const speed = event.target.value;
|
||||
fetch(`/setSpeed?address=${selectedLoco.address}&speed=${speed}`, { method: 'POST' });
|
||||
selectedLoco.setSpeed(speed);
|
||||
updateSpeedValue(speed);
|
||||
addLogMessage(`Speed set to ${speed} for address ${selectedLoco.address}`);
|
||||
});
|
||||
|
||||
document.querySelectorAll('.address-button').forEach(button => {
|
||||
button.addEventListener('click', () => {
|
||||
// Supprimer la classe 'selected' de tous les boutons
|
||||
document.querySelectorAll('.address-button').forEach(btn => btn.classList.remove('selected'));
|
||||
// Ajouter la classe 'selected' au bouton cliqué
|
||||
button.classList.add('selected');
|
||||
// Mettre à jour la locomotive sélectionnée
|
||||
const address = button.getAttribute('data-address');
|
||||
selectedLoco = locos[address];
|
||||
// Envoyer l'adresse au serveur
|
||||
fetch(`/setAddress?address=${address}`, { method: 'POST' });
|
||||
// Mettre à jour l'interface utilisateur avec les valeurs de la locomotive sélectionnée
|
||||
updateUI();
|
||||
addLogMessage(`Locomotive selected with address ${address}`);
|
||||
});
|
||||
});
|
||||
|
||||
document.querySelectorAll('.function-button').forEach(button => {
|
||||
button.addEventListener('click', () => {
|
||||
if (selectedLoco) {
|
||||
const functionId = button.getAttribute('data-function');
|
||||
const newState = !selectedLoco.functions[functionId];
|
||||
fetch(`/setFunction?address=${selectedLoco.address}&function=${functionId}&power=${newState ? 1 : 0}`, { method: 'POST' })
|
||||
.then(() => {
|
||||
selectedLoco.setFunction(functionId, newState);
|
||||
if (newState) {
|
||||
button.classList.add('active');
|
||||
addLogMessage(`Function F ${functionId} activated for address ${selectedLoco.address}`);
|
||||
} else {
|
||||
button.classList.remove('active');
|
||||
addLogMessage(`Function F ${functionId} deactivated for address ${selectedLoco.address}`);
|
||||
}
|
||||
});
|
||||
}
|
||||
});
|
||||
});
|
||||
|
||||
function updateSpeedValue(speed) {
|
||||
const speedValue = document.getElementById('speedValue');
|
||||
const percentage = (speed / 1000) * 100;
|
||||
speedValue.textContent = Math.round(percentage);
|
||||
}
|
||||
105
Railuino/data/style.css
Normal file
105
Railuino/data/style.css
Normal file
@@ -0,0 +1,105 @@
|
||||
body {
|
||||
font-family: Arial, sans-serif;
|
||||
}
|
||||
|
||||
h1 {
|
||||
text-align: center;
|
||||
}
|
||||
|
||||
.log-window {
|
||||
border: 1px solid #ccc;
|
||||
padding: 10px;
|
||||
margin-top: 20px;
|
||||
margin-bottom: 20px;
|
||||
max-height: 150px;
|
||||
overflow-y: scroll;
|
||||
background-color: #f9f9f9;
|
||||
font-family: monospace;
|
||||
font-size: 12px;
|
||||
}
|
||||
|
||||
.toggle-button {
|
||||
color: white;
|
||||
border: none;
|
||||
padding: 10px 20px;
|
||||
margin: 10px;
|
||||
cursor: pointer;
|
||||
background-color: green;
|
||||
}
|
||||
|
||||
.normal-button {
|
||||
color: white;
|
||||
border: none;
|
||||
padding: 10px 20px;
|
||||
margin: 10px;
|
||||
cursor: pointer;
|
||||
background-color: #a81b9c;
|
||||
}
|
||||
|
||||
.toggle-button.power-on {
|
||||
background-color: red;
|
||||
}
|
||||
|
||||
.toggle-button.power-off {
|
||||
background-color: green;
|
||||
}
|
||||
|
||||
.slider-container {
|
||||
display: flex;
|
||||
align-items: center;
|
||||
justify-content: center;
|
||||
margin-top: 20px;
|
||||
}
|
||||
|
||||
#speedSlider {
|
||||
width: 70%;
|
||||
margin: 0 10px;
|
||||
}
|
||||
|
||||
.slider-label {
|
||||
font-weight: bold;
|
||||
margin: 0 10px;
|
||||
}
|
||||
|
||||
.speed-percentage {
|
||||
text-align: center;
|
||||
margin-top: 10px;
|
||||
font-size: 1.2em;
|
||||
margin-bottom: 20px;
|
||||
}
|
||||
|
||||
.image-buttons {
|
||||
display: flex;
|
||||
justify-content: center;
|
||||
}
|
||||
|
||||
.address-button {
|
||||
margin: 0 10px;
|
||||
width: 90px;
|
||||
height: 60px;
|
||||
cursor: pointer;
|
||||
}
|
||||
|
||||
.address-button.selected {
|
||||
border: 1px solid black;
|
||||
}
|
||||
|
||||
.function-buttons {
|
||||
display: flex;
|
||||
flex-wrap: wrap;
|
||||
justify-content: center;
|
||||
}
|
||||
|
||||
.function-button {
|
||||
margin: 5px;
|
||||
padding: 10px 20px;
|
||||
cursor: pointer;
|
||||
background-color: lightgray;
|
||||
border: 1px solid #ccc;
|
||||
border-radius: 5px;
|
||||
}
|
||||
|
||||
.function-button.active {
|
||||
background-color: rgb(74, 72, 72);
|
||||
color: white;
|
||||
}
|
||||
BIN
Railuino/examples/.DS_Store
vendored
Normal file
BIN
Railuino/examples/.DS_Store
vendored
Normal file
Binary file not shown.
BIN
Railuino/examples/01.Controller/.DS_Store
vendored
Normal file
BIN
Railuino/examples/01.Controller/.DS_Store
vendored
Normal file
Binary file not shown.
BIN
Railuino/examples/01.Controller/CV/.DS_Store
vendored
Normal file
BIN
Railuino/examples/01.Controller/CV/.DS_Store
vendored
Normal file
Binary file not shown.
68
Railuino/examples/01.Controller/CV/CV_new.ino
Normal file
68
Railuino/examples/01.Controller/CV/CV_new.ino
Normal file
@@ -0,0 +1,68 @@
|
||||
/*********************************************************************
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* This exemple is the update of examples/01.Controller/CV/CV_new.ino
|
||||
*/
|
||||
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
const uint16_t LOCO = ADDR_MFX + 7; // Change with your own address
|
||||
|
||||
const bool DEBUG = false;
|
||||
const uint64_t TIMEOUT = 500; // ms
|
||||
const uint16_t HASH = 0x00;
|
||||
const bool LOOPBACK = false;
|
||||
|
||||
TrackController ctrl(HASH, DEBUG, TIMEOUT, LOOPBACK); // Instance de la classe TrackController, création de l'objet ctrl.
|
||||
|
||||
void showRegister(uint16_t, String);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial)
|
||||
;
|
||||
|
||||
ctrl.begin();
|
||||
Serial.print("Power on\n\n");
|
||||
ctrl.setPower(true);
|
||||
|
||||
showRegister(1, "Address");
|
||||
showRegister(2, "Min. Voltage");
|
||||
showRegister(3, "Accel. time");
|
||||
showRegister(4, "Decel. time");
|
||||
showRegister(5, "Max. speed");
|
||||
showRegister(6, "Avg. speed");
|
||||
showRegister(7, "Version");
|
||||
showRegister(8, "Manufacturer");
|
||||
|
||||
Serial.println("\n\nSystem stopped. Need to reset.");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
}// Nothing to do
|
||||
|
||||
void showRegister(uint16_t i, String label)
|
||||
{
|
||||
uint8_t b = 0;
|
||||
|
||||
if (ctrl.readConfig(LOCO, i, &b))
|
||||
Serial.print("Register "+label+" : "+b+"\n");
|
||||
}
|
||||
BIN
Railuino/examples/01.Controller/Direction/.DS_Store
vendored
Normal file
BIN
Railuino/examples/01.Controller/Direction/.DS_Store
vendored
Normal file
Binary file not shown.
68
Railuino/examples/01.Controller/Direction/Direction_new.ino
Normal file
68
Railuino/examples/01.Controller/Direction/Direction_new.ino
Normal file
@@ -0,0 +1,68 @@
|
||||
/*********************************************************************
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* This exemple is the update of examples/01.Controller/Direction/Direction.ino
|
||||
*/
|
||||
|
||||
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
const uint16_t LOCO = ADDR_MFX + 7; // Change with your own address
|
||||
|
||||
const uint16_t PAUSE = 10UL * 1000UL;
|
||||
|
||||
const bool DEBUG = false;
|
||||
const uint64_t TIMEOUT = 500; // ms
|
||||
const uint16_t HASH = 0x00;
|
||||
const bool LOOPBACK = false;
|
||||
|
||||
TrackController ctrl(HASH, DEBUG, TIMEOUT, LOOPBACK); // Instance de la classe TrackController, création de l'objet ctrl.
|
||||
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
ctrl.begin();
|
||||
Serial.println("Power on");
|
||||
ctrl.setPower(true);
|
||||
Serial.println("Headlights on");
|
||||
ctrl.setLocoFunction(LOCO, 0, 1);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
byte b;
|
||||
|
||||
ctrl.setLocoDirection(LOCO, DIR_FORWARD);
|
||||
if (ctrl.getLocoDirection(LOCO, &b)) {
|
||||
Serial.print("Direction is ");
|
||||
Serial.println(b == DIR_FORWARD ? "forward" : "reverse");
|
||||
}
|
||||
|
||||
delay(PAUSE);
|
||||
|
||||
ctrl.setLocoDirection(LOCO, DIR_REVERSE);
|
||||
if (ctrl.getLocoDirection(LOCO, &b)) {
|
||||
Serial.print("Direction is ");
|
||||
Serial.println(b == DIR_FORWARD ? "forward" : "reverse");
|
||||
}
|
||||
|
||||
delay(PAUSE);
|
||||
}
|
||||
|
||||
BIN
Railuino/examples/01.Controller/Function/.DS_Store
vendored
Normal file
BIN
Railuino/examples/01.Controller/Function/.DS_Store
vendored
Normal file
Binary file not shown.
82
Railuino/examples/01.Controller/Function/Function_new.ino
Normal file
82
Railuino/examples/01.Controller/Function/Function_new.ino
Normal file
@@ -0,0 +1,82 @@
|
||||
/*********************************************************************
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* This exemple is the update of examples/01.Controller/Function/Function_new.ino
|
||||
*/
|
||||
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
const uint16_t LOCO = ADDR_MFX + 7; // Change with your own address
|
||||
|
||||
const uint16_t PAUSE = 5UL * 1000UL;
|
||||
|
||||
const bool DEBUG = false;
|
||||
const uint64_t TIMEOUT = 500; // ms
|
||||
const uint16_t HASH = 0x00;
|
||||
const bool LOOPBACK = false;
|
||||
|
||||
TrackController ctrl(HASH, DEBUG, TIMEOUT, LOOPBACK); // Instance de la classe TrackController, création de l'objet ctrl.
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial)
|
||||
;
|
||||
|
||||
ctrl.begin();
|
||||
Serial.println("Power on");
|
||||
ctrl.setPower(true);
|
||||
|
||||
byte b;
|
||||
|
||||
for (uint8_t i = 0; i <= 12; i++)
|
||||
{
|
||||
// Serial.print("Function ");
|
||||
// Serial.print(i, DEC);
|
||||
|
||||
ctrl.setLocoFunction(LOCO, i, 1);
|
||||
if (ctrl.getLocoFunction(LOCO, i, &b))
|
||||
{
|
||||
Serial.print("Function ");
|
||||
Serial.print(i, DEC);
|
||||
Serial.println(b ? " is on" : " is off");
|
||||
}
|
||||
|
||||
delay(PAUSE);
|
||||
|
||||
ctrl.setLocoFunction(LOCO, i, 0);
|
||||
if (ctrl.getLocoFunction(LOCO, i, &b))
|
||||
{
|
||||
Serial.print("Function ");
|
||||
Serial.print(i, DEC);
|
||||
Serial.println(b ? " is on" : " is off");
|
||||
}
|
||||
|
||||
delay(PAUSE);
|
||||
}
|
||||
|
||||
Serial.println("Power off");
|
||||
ctrl.setPower(false);
|
||||
|
||||
Serial.println("System stopped. Need to reset.");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
} // Nothing to do
|
||||
65
Railuino/examples/01.Controller/Headlight/Headlight_new.ino
Normal file
65
Railuino/examples/01.Controller/Headlight/Headlight_new.ino
Normal file
@@ -0,0 +1,65 @@
|
||||
/*********************************************************************
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* This exemple is the update of examples/01.Controller/Headlight/Headlight_new.ino
|
||||
*/
|
||||
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
const uint16_t LOCO = ADDR_MFX + 7; // Change with your own address
|
||||
|
||||
const uint16_t PAUSE = 5UL * 1000UL;
|
||||
|
||||
const bool DEBUG = false;
|
||||
const uint64_t TIMEOUT = 500; // ms
|
||||
const uint16_t HASH = 0x00;
|
||||
const bool LOOPBACK = false;
|
||||
|
||||
TrackController ctrl(HASH, DEBUG, TIMEOUT, LOOPBACK); // Instance de la classe TrackController, création de l'objet ctrl.
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
ctrl.begin();
|
||||
Serial.println("Power on");
|
||||
ctrl.setPower(true);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
byte b;
|
||||
|
||||
ctrl.setLocoFunction(LOCO, 0, 1);
|
||||
if (ctrl.getLocoFunction(LOCO, 0, &b)) {
|
||||
Serial.print("Lights are ");
|
||||
Serial.println(b ? "on" : "off");
|
||||
}
|
||||
|
||||
delay(PAUSE);
|
||||
|
||||
ctrl.setLocoFunction(LOCO, 0, 0);
|
||||
if (ctrl.getLocoFunction(LOCO, 0, &b)) {
|
||||
Serial.print("Lights are ");
|
||||
Serial.println(b ? "on" : "off");
|
||||
}
|
||||
|
||||
delay(PAUSE);
|
||||
}
|
||||
|
||||
|
||||
BIN
Railuino/examples/01.Controller/Power/.DS_Store
vendored
Normal file
BIN
Railuino/examples/01.Controller/Power/.DS_Store
vendored
Normal file
Binary file not shown.
48
Railuino/examples/01.Controller/Power/Power_new.ino
Normal file
48
Railuino/examples/01.Controller/Power/Power_new.ino
Normal file
@@ -0,0 +1,48 @@
|
||||
/*********************************************************************
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* This exemple is the update of examples/01.Controller/Power/Power.ino
|
||||
*/
|
||||
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
const uint16_t PAUSE = 5000;
|
||||
const bool DEBUG = true;
|
||||
const uint64_t TIMEOUT = 500; // ms
|
||||
const uint16_t HASH = 0x00;
|
||||
const bool LOOPBACK = false;
|
||||
|
||||
TrackController ctrl(HASH, DEBUG, TIMEOUT, LOOPBACK); // Instance de la classe TrackController, création de l'objet ctrl.
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
ctrl.begin(); // Lancement du contrôleur
|
||||
}
|
||||
|
||||
void loop() {
|
||||
ctrl.setPower(true); // Allumage de la centrale
|
||||
delay(PAUSE);
|
||||
|
||||
ctrl.setPower(false); // Extinction de la centrale
|
||||
delay(PAUSE);
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,55 @@
|
||||
/*********************************************************************
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* This exemple is the update of examples/01.Controller/SerialCommand/SerialCommand.ino
|
||||
*/
|
||||
|
||||
/*
|
||||
* Exemple :
|
||||
power 1
|
||||
speed 16391 100
|
||||
function 16391 0 1
|
||||
*/
|
||||
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
const bool DEBUG = false;
|
||||
const uint64_t TIMEOUT = 500; // ms
|
||||
const uint16_t HASH = 0x00;
|
||||
const bool LOOPBACK = false;
|
||||
|
||||
TrackController ctrl(HASH, DEBUG, TIMEOUT, LOOPBACK); // Instance de la classe TrackController, création de l'objet ctrl.
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial)
|
||||
;
|
||||
ctrl.begin();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (Serial.available())
|
||||
{
|
||||
String command = Serial.readStringUntil('\n');
|
||||
Serial.println(command);
|
||||
ctrl.handleUserCommands(command);
|
||||
}
|
||||
}
|
||||
94
Railuino/examples/01.Controller/SerialCommand/TCPCommand.ino
Normal file
94
Railuino/examples/01.Controller/SerialCommand/TCPCommand.ino
Normal file
@@ -0,0 +1,94 @@
|
||||
/*********************************************************************
|
||||
* 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 "Config.h"
|
||||
#include "TrackController.h"
|
||||
//----------------------------------------------------------------------------------------
|
||||
// Include files
|
||||
//----------------------------------------------------------------------------------------
|
||||
|
||||
#include <ACAN_ESP32.h> // https://github.com/pierremolinaro/acan-esp32.git
|
||||
#include <Arduino.h>
|
||||
#include <WiFi.h>
|
||||
|
||||
const uint16_t LOCO = ADDR_MFX + 7; // Change with your own address
|
||||
const bool DEBUG = true;
|
||||
|
||||
byte cBuffer[13]; // CAN buffer
|
||||
byte sBuffer[13]; // Serial buffer
|
||||
|
||||
TrackController ctrl(0xDF24, DEBUG);
|
||||
|
||||
//----------------------------------------------------------------------------------------
|
||||
// TCP/WIFI-ETHERNET
|
||||
//----------------------------------------------------------------------------------------
|
||||
|
||||
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 = 15731;
|
||||
WiFiServer server(port);
|
||||
WiFiClient client;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial)
|
||||
;
|
||||
|
||||
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.begin();
|
||||
|
||||
ctrl.begin();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
while (!client) // listen for incoming clients
|
||||
client = server.available();
|
||||
if (client.connected())
|
||||
{
|
||||
if (client.available())
|
||||
{
|
||||
String command = client.readStringUntil('\n');
|
||||
|
||||
Serial.println(command);
|
||||
ctrl.handleUserCommands(command);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// if (!client.connected())
|
||||
// {
|
||||
// Serial.println("Client disconnected.");
|
||||
// client.stop();
|
||||
// }
|
||||
308
Railuino/examples/01.Controller/SerialCommand/WebCommand
Normal file
308
Railuino/examples/01.Controller/SerialCommand/WebCommand
Normal file
@@ -0,0 +1,308 @@
|
||||
|
||||
|
||||
#ifndef ARDUINO_ARCH_ESP32
|
||||
#error "Select an ESP32 board"
|
||||
#endif
|
||||
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <WebServer.h>
|
||||
#include <SPIFFS.h>
|
||||
#include <ACAN_ESP32.h>
|
||||
#include "Config.h"
|
||||
#include "TrackController.h"
|
||||
|
||||
bool powerState = false; // Variable globale pour suivre l'état de l'alimentation
|
||||
const bool DEBUG = true;
|
||||
|
||||
byte cBuffer[13];
|
||||
byte sBuffer[13];
|
||||
|
||||
const gpio_num_t can_rx_pin = GPIO_NUM_22;
|
||||
const gpio_num_t can_tx_pin = GPIO_NUM_23;
|
||||
|
||||
//TrackController ctrl; // Instance without parameters
|
||||
//TrackController ctrl(500); // Instance by changing the default exchangeMessage timeout from 1000ms to 500ms
|
||||
//TrackController ctrl(0xDF24, DEBUG); // Instance with hash, debug and defaut exchangeMessage timeout = 1000
|
||||
TrackController ctrl(0xDF24, DEBUG, 500); // Instance with hash, debug and exchangeMessage timeout = 500
|
||||
|
||||
|
||||
|
||||
// const char *ssid = "**********";
|
||||
// const char *password = "**********";
|
||||
const char *ssid = "Livebox-BC90";
|
||||
const char *password = "V9b7qzKFxdQfbMT4Pa";
|
||||
|
||||
|
||||
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();
|
||||
void handleCss();
|
||||
void handleJs();
|
||||
void handleImage1();
|
||||
void handleImage2();
|
||||
void handleImage3();
|
||||
void handleImage4();
|
||||
void handleFavinco();
|
||||
void handleSetPower();
|
||||
void handleSetStop();
|
||||
void handleSetSystemHalt();
|
||||
void handleSetDirection();
|
||||
void handleSetSpeed();
|
||||
void handleSetAddress();
|
||||
void handleSetFunction();
|
||||
void handleNotFound();
|
||||
|
||||
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(can_rx_pin, can_tx_pin);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
server.handleClient();
|
||||
}
|
||||
|
||||
|
||||
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");
|
||||
}
|
||||
BIN
Railuino/examples/01.Controller/Speed/.DS_Store
vendored
Normal file
BIN
Railuino/examples/01.Controller/Speed/.DS_Store
vendored
Normal file
Binary file not shown.
BIN
Railuino/examples/01.Controller/Test_address_loco.zip
Normal file
BIN
Railuino/examples/01.Controller/Test_address_loco.zip
Normal file
Binary file not shown.
39
Railuino/include/README
Normal file
39
Railuino/include/README
Normal file
@@ -0,0 +1,39 @@
|
||||
|
||||
This directory is intended for project header files.
|
||||
|
||||
A header file is a file containing C declarations and macro definitions
|
||||
to be shared between several project source files. You request the use of a
|
||||
header file in your project source file (C, C++, etc) located in `src` folder
|
||||
by including it, with the C preprocessing directive `#include'.
|
||||
|
||||
```src/main.c
|
||||
|
||||
#include "header.h"
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
```
|
||||
|
||||
Including a header file produces the same results as copying the header file
|
||||
into each source file that needs it. Such copying would be time-consuming
|
||||
and error-prone. With a header file, the related declarations appear
|
||||
in only one place. If they need to be changed, they can be changed in one
|
||||
place, and programs that include the header file will automatically use the
|
||||
new version when next recompiled. The header file eliminates the labor of
|
||||
finding and changing all the copies as well as the risk that a failure to
|
||||
find one copy will result in inconsistencies within a program.
|
||||
|
||||
In C, the usual convention is to give header files names that end with `.h'.
|
||||
It is most portable to use only letters, digits, dashes, and underscores in
|
||||
header file names, and at most one dot.
|
||||
|
||||
Read more about using header files in official GCC documentation:
|
||||
|
||||
* Include Syntax
|
||||
* Include Operation
|
||||
* Once-Only Headers
|
||||
* Computed Includes
|
||||
|
||||
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
||||
39
Railuino/lib/README
Normal file
39
Railuino/lib/README
Normal file
@@ -0,0 +1,39 @@
|
||||
Version 0.9.1 de la bibliothèque Railuino de Joerg Pleumann dont le dépôt git se trouve à cet emplacement : https://code.google.com/archive/p/railuino/
|
||||
|
||||
Cette bibliothèque est sous licence GNU LESSER GENERAL PUBLIC LICENSE - Version 2.1, February 1999
|
||||
|
||||
Copyright (C) 2012 Joerg Pleumann
|
||||
|
||||
Cette version 9.0.1 est une réécriture profonde à partir de la version 0.9.0, dernière version publiée à ma connaissance et qui date de 2013 !
|
||||
|
||||
Dans sa version 0.9.0, cette bibliothèque est très bien écrite mais elle est ancienne (2013, c’est beaucoup en programmation), elle n’est pas adaptée aux nouveaux microcontrôleurs comme l’ESP32, comporte quelques manques (comme la reconnaissance automatique en MFX) et doit être optimisée par rapport aux normes C++ 11 et suivantes. Je suis actuellement en train de réécrire certaines parties de cette bibliothèque que je teste au fur et à mesure.
|
||||
|
||||
Je ne m’intéresse actuellement qu’à la version ESP32. Je publie mon travail sur ce git à chaque évolution majeure.
|
||||
|
||||
Les exemples originaux pour la mise en œuvre et les tests de cette bibliothèque sont encore d’actualité mais doivent aussi être adaptés.
|
||||
|
||||
Vous trouverez dans le dossier « exemples » les fichiers mis à jour qui portent les noms originaux auxquels j’ai ajouté « _new ».
|
||||
|
||||
Les fichiers originaux sont conservés à titre de mémoire et de comparaison.
|
||||
|
||||
*****************************************************************************************************
|
||||
|
||||
Version 0.9.1 of Joerg Pleumann's Railuino library, the git repository for which can be found at: https://code.google.com/archive/p/railuino/
|
||||
|
||||
This library is licensed under the GNU LESSER GENERAL PUBLIC LICENSE - Version 2.1, February 1999
|
||||
|
||||
Copyright (C) 2012 Joerg Pleumann
|
||||
|
||||
This version 9.0.1 is a thorough rewrite of version 0.9.0, the last version published to my knowledge, which dates back to 2013!
|
||||
|
||||
In its version 0.9.0, this library is very well written but it is old (2013 is a long time in programming), it is not adapted to new microcontrollers such as the ESP32, has a few shortcomings (such as automatic recognition in MFX) and needs to be optimised in relation to the C++ 11 and later standards. I'm currently rewriting parts of this library and testing them as I go along.
|
||||
|
||||
I'm currently only interested in the ESP32 version. I publish my work on this git whenever there is a major change.
|
||||
|
||||
The original examples for implementing and testing this library are still relevant, but they also need to be adapted.
|
||||
|
||||
You'll find the updated files in the "examples" folder, which have the original names to which I've added "_new".
|
||||
|
||||
The original files are kept for memory and comparison.
|
||||
|
||||
|
||||
36
Railuino/platformio.ini
Normal file
36
Railuino/platformio.ini
Normal file
@@ -0,0 +1,36 @@
|
||||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[platformio]
|
||||
default_envs =
|
||||
uno
|
||||
megaatmega2560
|
||||
esp32dev
|
||||
|
||||
[env:esp32dev]
|
||||
platform = espressif32
|
||||
board = esp32dev
|
||||
framework = arduino
|
||||
lib_deps =
|
||||
pierremolinaro/ACAN_ESP32@=1.1.2
|
||||
|
||||
[env:uno]
|
||||
platform = atmelavr
|
||||
board = uno
|
||||
framework = arduino
|
||||
lib_deps =
|
||||
pierremolinaro/ACAN2515@=2.1.3
|
||||
|
||||
[env:megaatmega2560]
|
||||
platform = atmelavr
|
||||
board = megaatmega2560
|
||||
framework = arduino
|
||||
lib_deps =
|
||||
pierremolinaro/ACAN2515@=2.1.3
|
||||
BIN
Railuino/src/.DS_Store
vendored
Normal file
BIN
Railuino/src/.DS_Store
vendored
Normal file
Binary file not shown.
86
Railuino/src/Config.h
Normal file
86
Railuino/src/Config.h
Normal 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
|
||||
890
Railuino/src/TrackController.cpp
Normal file
890
Railuino/src/TrackController.cpp
Normal 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);
|
||||
}
|
||||
//}
|
||||
}
|
||||
349
Railuino/src/TrackController.h
Normal file
349
Railuino/src/TrackController.h
Normal 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
|
||||
|
||||
123
Railuino/src/TrackMessage.cpp
Normal file
123
Railuino/src/TrackMessage.cpp
Normal 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;
|
||||
}
|
||||
91
Railuino/src/TrackMessage.h
Normal file
91
Railuino/src/TrackMessage.h
Normal 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
|
||||
0
Railuino/src/TrackReporterIOX.cpp
Normal file
0
Railuino/src/TrackReporterIOX.cpp
Normal file
0
Railuino/src/TrackReporterS88.cpp
Normal file
0
Railuino/src/TrackReporterS88.cpp
Normal file
272
Railuino/src/main.cpp
Normal file
272
Railuino/src/main.cpp
Normal 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();
|
||||
}
|
||||
11
Railuino/test/README
Normal file
11
Railuino/test/README
Normal file
@@ -0,0 +1,11 @@
|
||||
|
||||
This directory is intended for PlatformIO Test Runner and project tests.
|
||||
|
||||
Unit Testing is a software testing method by which individual units of
|
||||
source code, sets of one or more MCU program modules together with associated
|
||||
control data, usage procedures, and operating procedures, are tested to
|
||||
determine whether they are fit for use. Unit testing finds problems early
|
||||
in the development cycle.
|
||||
|
||||
More information about PlatformIO Unit Testing:
|
||||
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html
|
||||
Reference in New Issue
Block a user