mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2025-01-24 03:18:51 +01:00
Merge branch 'motor-drivers'
This commit is contained in:
commit
a180700f3a
@ -89,7 +89,18 @@ int inline analogReadFast(uint8_t ADCpin)
|
||||
return adc;
|
||||
}
|
||||
|
||||
#elif defined(ARDUINO_AVR_UNO_WIFI_REV2) || defined(ARDUINO_AVR_NANO_EVERY)
|
||||
|
||||
int inline analogReadFast(uint8_t ADCpin)
|
||||
{ byte ADC0CTRLCoriginal = ADC0.CTRLC;
|
||||
ADC0.CTRLC = (ADC0CTRLCoriginal & 0b00110000) + 0b01000011;
|
||||
int adc = analogRead(ADCpin);
|
||||
ADC0.CTRLC = ADC0CTRLCoriginal;
|
||||
return adc;
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
int inline analogReadFast(uint8_t ADCpin)
|
||||
{ byte ADCSRAoriginal = ADCSRA;
|
||||
ADCSRA = (ADCSRA & B11111000) | 4;
|
||||
|
42
CVReader.ino
42
CVReader.ino
@ -24,6 +24,14 @@
|
||||
#include "DCCEXParser.h"
|
||||
#include "WifiInterface.h"
|
||||
|
||||
#ifdef ARDUINO_AVR_UNO
|
||||
#include <SoftwareSerial.h>
|
||||
SoftwareSerial Serial1(15,16); // YOU must get thee pins correct to use Wifi on a UNO
|
||||
#define WIFI_BAUD 9600
|
||||
#else
|
||||
#define WIFI_BAUD 115200
|
||||
#endif
|
||||
|
||||
// this code is here to demonstrate use of the DCC API and other techniques
|
||||
|
||||
// myFilter is an example of an OPTIONAL command filter used to intercept < > commands from
|
||||
@ -74,22 +82,26 @@ void setup() {
|
||||
|
||||
// Responsibility 1: Start the usb connection for diagnostics and possible JMRI input
|
||||
// DIAGSERAL is normally Serial but uses SerialUSB on a SAMD processor
|
||||
DIAGSERIAL.begin(115200);
|
||||
while(!DIAGSERIAL);
|
||||
|
||||
// Responsibility 2: Start the DCC engine.
|
||||
DCC::begin();
|
||||
DIAGSERIAL.begin(115200);
|
||||
while(!DIAGSERIAL);
|
||||
|
||||
// Responsibility 2: Start the DCC engine.
|
||||
// Note: this provides DCC with two motor drivers, main and prog, which handle the motor shield(s)
|
||||
// Standard supported devices have pre-configured macros but custome hardware installations require
|
||||
// detailed pin mappings and may also require modified subclasses of the MotorDriver to implement specialist logic.
|
||||
|
||||
DCC::begin(STANDARD_MOTOR_SHIELD);
|
||||
|
||||
// Responsibility 3: Optionally Start the WiFi interface if required.
|
||||
// Responsibility 3: **Optionally** Start the WiFi interface if required.
|
||||
// NOTE: On a Uno you will have to provide a SoftwareSerial
|
||||
// configured for the pins connected to the Wifi card
|
||||
// and a 9600 baud rate.
|
||||
// setup(serial, F(router name), F(password) , port)
|
||||
//
|
||||
#ifdef WIFI
|
||||
Serial1.begin(115200);
|
||||
WifiInterface::setup(Serial1, F(WIFI_CONNECT_TO_SSID), F(WIFI_CONNECT_PASSWORD),F("DCCEX"),F("CVReader"),3532); // (3532 is 0xDCC decimal... )
|
||||
#endif
|
||||
// (port 3532 is 0xDCC decimal.)
|
||||
|
||||
|
||||
Serial1.begin(WIFI_BAUD);
|
||||
WifiInterface::setup(Serial1, F("BTHub5-M6PT"), F("49de8d4862"),F("DCCEX"),F("CVReader"),3532);
|
||||
|
||||
// This is just for demonstration purposes
|
||||
DIAG(F("\n===== CVReader demonstrating DCC::getLocoId() call ==========\n"));
|
||||
@ -98,7 +110,7 @@ void setup() {
|
||||
|
||||
// Optionally tell the command parser to use my example filter.
|
||||
// This will intercept JMRI commands from both USB and Wifi
|
||||
DCCEXParser::setFilter(myFilter);
|
||||
DCCEXParser::setFilter(myFilter);
|
||||
|
||||
DIAG(F("\nReady for JMRI commands\n"));
|
||||
|
||||
@ -115,13 +127,11 @@ void loop() {
|
||||
serialParser.loop(DIAGSERIAL);
|
||||
|
||||
// Responsibility 3: Optionally handle any incoming WiFi traffic
|
||||
#ifdef WIFI
|
||||
WifiInterface::loop();
|
||||
#endif
|
||||
|
||||
// Your additional code
|
||||
// Your additional loop code
|
||||
|
||||
// OPtionally report any decrease in memory (will automatically trigger on first call)
|
||||
// Optionally report any decrease in memory (will automatically trigger on first call)
|
||||
int freeNow=freeMemory();
|
||||
if (freeNow<ramLowWatermark) {
|
||||
ramLowWatermark=freeNow;
|
||||
|
47
Config.h
47
Config.h
@ -1,37 +1,36 @@
|
||||
#ifndef Config_h
|
||||
#define Config_h
|
||||
|
||||
// Define these if you have a WiFi board on Serial1
|
||||
#define WIFI
|
||||
#define WIFI_CONNECT_TO_SSID "RPi-JMRI"
|
||||
#define WIFI_CONNECT_PASSWORD "rpI-jmri"
|
||||
// *** PLEASE NOTE *** THIS FILE IS **NOT** INTENDED TO BE EDITED WHEN CONFIGURING A SYSTEM.
|
||||
// It will be overwritten if the library is updated.
|
||||
|
||||
// This hardware configuration would normally be setup using a bunch of #ifdefs.
|
||||
// This file contains configurations for known/supported motor shields.
|
||||
// A configuration defined by macro here can be used in your sketch.
|
||||
// A custom hardware setup will require your sketch to create MotorDriver instances
|
||||
// similar to those defined here, WITHOUT editing this file.
|
||||
|
||||
|
||||
const byte UNUSED_PIN = 255;
|
||||
|
||||
const byte MAIN_POWER_PIN = 3;
|
||||
const byte MAIN_SIGNAL_PIN = 12;
|
||||
const byte MAIN_SIGNAL_PIN_ALT = UNUSED_PIN; // for hardware that flipflops signal pins
|
||||
const byte MAIN_SENSE_PIN = A0;
|
||||
const byte MAIN_BRAKE_PIN = 9;
|
||||
const byte MAIN_FAULT_PIN = UNUSED_PIN;
|
||||
// MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin, byte current_pin,
|
||||
// float senseFactor, unsigned int tripMilliamps, byte faultPin);
|
||||
|
||||
// Arduino standard Motor Shield
|
||||
#define STANDARD_MOTOR_SHIELD \
|
||||
new MotorDriver(3 , 12, UNUSED_PIN, UNUSED_PIN, A0, 2.99, 2000, UNUSED_PIN), \
|
||||
new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 250 , UNUSED_PIN)
|
||||
|
||||
const int MAIN_MAX_MILLIAMPS=2000;
|
||||
const float MAIN_SENSE_FACTOR=2.99; // analgRead(MAIN_SENSE_PIN) * MAIN_SENSE_FACTOR = milliamps
|
||||
|
||||
const byte PROG_POWER_PIN = 11;
|
||||
const byte PROG_SIGNAL_PIN = 13;
|
||||
const byte PROG_SIGNAL_PIN_ALT = UNUSED_PIN; // for hardware that flipflops signal pins
|
||||
const byte PROG_SENSE_PIN = A1;
|
||||
const byte PROG_BRAKE_PIN = 8;
|
||||
const byte PROG_FAULT_PIN = UNUSED_PIN;
|
||||
|
||||
const int PROG_MAX_MILLIAMPS=250;
|
||||
const float PROG_SENSE_FACTOR=2.99; // analgRead(PROG_SENSE_PIN) * PROG_SENSE_FACTOR = milliamps
|
||||
// Pololu Motor Shield
|
||||
#define POLOLU_MOTOR_SHIELD \
|
||||
new MotorDriver(4, 7, UNUSED_PIN, 9 , A0, 18, 2000, 12), \
|
||||
new MotorDriver(2, 8, UNUSED_PIN, 10, A1, 18, 250 , UNUSED_PIN)
|
||||
|
||||
// Allocations with memory implications..!
|
||||
// Base system takes approx 900 bytes + 8 per loco. Turnouts, Sensors etc are dynamically created
|
||||
const byte MAX_LOCOS=50;
|
||||
#ifdef ARDUINO_AVR_UNO
|
||||
const byte MAX_LOCOS=20;
|
||||
#else
|
||||
const byte MAX_LOCOS=50;
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
6
DCC.cpp
6
DCC.cpp
@ -20,7 +20,7 @@
|
||||
#include "DCC.h"
|
||||
#include "DCCWaveform.h"
|
||||
#include "DIAG.h"
|
||||
#include "Hardware.h"
|
||||
|
||||
|
||||
// This module is responsible for converting API calls into
|
||||
// messages to be sent to the waveform generator.
|
||||
@ -42,9 +42,9 @@ const byte FN_GROUP_4=0x08;
|
||||
const byte FN_GROUP_5=0x10;
|
||||
|
||||
|
||||
void DCC::begin() {
|
||||
void DCC::begin(MotorDriver * mainDriver, MotorDriver* progDriver) {
|
||||
debugMode=false;
|
||||
DCCWaveform::begin();
|
||||
DCCWaveform::begin(mainDriver,progDriver);
|
||||
}
|
||||
|
||||
void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) {
|
||||
|
3
DCC.h
3
DCC.h
@ -20,6 +20,7 @@
|
||||
#define DCC_h
|
||||
#include <Arduino.h>
|
||||
#include "Config.h"
|
||||
#include "MotorDriver.h"
|
||||
|
||||
typedef void (*ACK_CALLBACK)(int result);
|
||||
|
||||
@ -49,7 +50,7 @@ SKIPTARGET=0xFF // jump to target
|
||||
class DCC {
|
||||
public:
|
||||
|
||||
static void begin();
|
||||
static void begin(MotorDriver * mainDriver, MotorDriver * progDriver);
|
||||
static void loop();
|
||||
|
||||
// Public DCC API functions
|
||||
|
@ -17,22 +17,29 @@
|
||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include "Hardware.h"
|
||||
|
||||
#include "DCCWaveform.h"
|
||||
#include "DIAG.h"
|
||||
#include "MotorDriver.h"
|
||||
#include <ArduinoTimers.h> // use IDE menu Tools..Manage Libraries to locate and install TimerOne
|
||||
|
||||
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true, (int)(MAIN_MAX_MILLIAMPS / MAIN_SENSE_FACTOR));
|
||||
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false, (int)(PROG_MAX_MILLIAMPS / PROG_SENSE_FACTOR));
|
||||
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
|
||||
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
|
||||
|
||||
const int ACK_MIN_PULSE_RAW=65 / PROG_SENSE_FACTOR;
|
||||
|
||||
bool DCCWaveform::progTrackSyncMain=false;
|
||||
|
||||
void DCCWaveform::begin() {
|
||||
Hardware::init();
|
||||
Hardware::setCallback(58, interruptHandler);
|
||||
mainTrack.beginTrack();
|
||||
progTrack.beginTrack();
|
||||
void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
|
||||
mainTrack.motorDriver=mainDriver;
|
||||
progTrack.motorDriver=progDriver;
|
||||
|
||||
TimerA.initialize();
|
||||
TimerA.setPeriod(58);
|
||||
TimerA.attachInterrupt(interruptHandler);
|
||||
TimerA.start();
|
||||
mainTrack.setPowerMode(POWERMODE::ON);
|
||||
progTrack.setPowerMode(POWERMODE::ON);
|
||||
|
||||
}
|
||||
|
||||
void DCCWaveform::loop() {
|
||||
@ -66,9 +73,8 @@ void DCCWaveform::interruptHandler() {
|
||||
const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
|
||||
|
||||
|
||||
DCCWaveform::DCCWaveform( byte preambleBits, bool isMain, int rawCurrentTrip) {
|
||||
DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
|
||||
// establish appropriate pins
|
||||
rawCurrentTripValue=rawCurrentTrip;
|
||||
isMainTrack = isMain;
|
||||
packetPending = false;
|
||||
memcpy(transmitPacket, idlePacket, sizeof(idlePacket));
|
||||
@ -80,11 +86,7 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain, int rawCurrentTrip) {
|
||||
bits_sent = 0;
|
||||
sampleDelay = 0;
|
||||
lastSampleTaken = millis();
|
||||
ackPending=false;
|
||||
}
|
||||
void DCCWaveform::beginTrack() {
|
||||
setPowerMode(POWERMODE::ON);
|
||||
|
||||
ackPending=false;
|
||||
}
|
||||
|
||||
POWERMODE DCCWaveform::getPowerMode() {
|
||||
@ -94,8 +96,7 @@ POWERMODE DCCWaveform::getPowerMode() {
|
||||
void DCCWaveform::setPowerMode(POWERMODE mode) {
|
||||
powerMode = mode;
|
||||
bool ison = (mode == POWERMODE::ON);
|
||||
Hardware::setPower(isMainTrack, ison);
|
||||
Hardware::setBrake(isMainTrack, !ison);
|
||||
motorDriver->setPower( ison);
|
||||
if (mode == POWERMODE::ON) delay(200);
|
||||
}
|
||||
|
||||
@ -104,7 +105,7 @@ void DCCWaveform::checkPowerOverload() {
|
||||
|
||||
if (millis() - lastSampleTaken < sampleDelay) return;
|
||||
lastSampleTaken = millis();
|
||||
int tripValue= rawCurrentTripValue;
|
||||
int tripValue= motorDriver->rawCurrentTripValue;
|
||||
if (!isMainTrack && (ackPending || progTrackSyncMain)) tripValue=ACK_CURRENT_TRIP;
|
||||
|
||||
switch (powerMode) {
|
||||
@ -113,7 +114,7 @@ void DCCWaveform::checkPowerOverload() {
|
||||
break;
|
||||
case POWERMODE::ON:
|
||||
// Check current
|
||||
lastCurrent = Hardware::getCurrentRaw(isMainTrack);
|
||||
lastCurrent = motorDriver->getCurrentRaw();
|
||||
if (lastCurrent <= tripValue) {
|
||||
sampleDelay = POWER_SAMPLE_ON_WAIT;
|
||||
if(power_good_counter<100)
|
||||
@ -122,8 +123,8 @@ void DCCWaveform::checkPowerOverload() {
|
||||
if (power_sample_overload_wait>POWER_SAMPLE_OVERLOAD_WAIT) power_sample_overload_wait=POWER_SAMPLE_OVERLOAD_WAIT;
|
||||
} else {
|
||||
setPowerMode(POWERMODE::OVERLOAD);
|
||||
unsigned int mA=Hardware::getCurrentMilliamps(isMainTrack,lastCurrent);
|
||||
unsigned int maxmA=Hardware::getCurrentMilliamps(isMainTrack,tripValue);
|
||||
unsigned int mA=motorDriver->convertToMilliamps(lastCurrent);
|
||||
unsigned int maxmA=motorDriver->convertToMilliamps(tripValue);
|
||||
DIAG(F("\n*** %S TRACK POWER OVERLOAD current=%d max=%d offtime=%l ***\n"), isMainTrack ? F("MAIN") : F("PROG"), mA, maxmA, power_sample_overload_wait);
|
||||
power_good_counter=0;
|
||||
sampleDelay = power_sample_overload_wait;
|
||||
@ -183,10 +184,11 @@ void DCCWaveform::setSignal(bool high) {
|
||||
if (progTrackSyncMain) {
|
||||
if (!isMainTrack) return; // ignore PROG track waveform while in sync
|
||||
// set both tracks to same signal
|
||||
Hardware::setSyncSignal(high);
|
||||
motorDriver->setSignal(high);
|
||||
progTrack.motorDriver->setSignal(high);
|
||||
return;
|
||||
}
|
||||
Hardware::setSignal(isMainTrack,high);
|
||||
motorDriver->setSignal(high);
|
||||
}
|
||||
|
||||
void DCCWaveform::interrupt2() {
|
||||
@ -264,8 +266,8 @@ int DCCWaveform::getLastCurrent() {
|
||||
|
||||
void DCCWaveform::setAckBaseline(bool debug) {
|
||||
if (isMainTrack) return;
|
||||
ackThreshold=Hardware::getCurrentRaw(false) + ACK_MIN_PULSE_RAW;
|
||||
if (debug) DIAG(F("\nACK-BASELINE %d/%dmA"),ackThreshold,Hardware::getCurrentMilliamps(false,ackThreshold));
|
||||
ackThreshold=motorDriver->getCurrentRaw() + (int)(65 / motorDriver->senseFactor);
|
||||
if (debug) DIAG(F("\nACK-BASELINE %d/%dmA"),ackThreshold,motorDriver->convertToMilliamps(ackThreshold));
|
||||
}
|
||||
|
||||
void DCCWaveform::setAckPending(bool debug) {
|
||||
@ -282,7 +284,7 @@ void DCCWaveform::setAckPending(bool debug) {
|
||||
byte DCCWaveform::getAck(bool debug) {
|
||||
if (ackPending) return (2); // still waiting
|
||||
if (debug) DIAG(F("\nACK-%S after %dmS max=%d/%dmA pulse=%duS"),ackDetected?F("OK"):F("FAIL"), ackCheckDuration,
|
||||
ackMaxCurrent,Hardware::getCurrentMilliamps(false,ackMaxCurrent), ackPulseDuration);
|
||||
ackMaxCurrent,motorDriver->convertToMilliamps(ackMaxCurrent), ackPulseDuration);
|
||||
if (ackDetected) return (1); // Yes we had an ack
|
||||
return(0); // pending set off but not detected means no ACK.
|
||||
}
|
||||
@ -296,7 +298,7 @@ void DCCWaveform::checkAck() {
|
||||
return;
|
||||
}
|
||||
|
||||
lastCurrent=Hardware::getCurrentRaw(false);
|
||||
lastCurrent=motorDriver->getCurrentRaw();
|
||||
if (lastCurrent > ackMaxCurrent) ackMaxCurrent=lastCurrent;
|
||||
// An ACK is a pulse lasting between MIN_ACK_PULSE_DURATION and MAX_ACK_PULSE_DURATION uSecs (refer @haba)
|
||||
|
||||
|
@ -19,12 +19,13 @@
|
||||
#ifndef DCCWaveform_h
|
||||
#define DCCWaveform_h
|
||||
#include "Config.h"
|
||||
#include "MotorDriver.h"
|
||||
|
||||
const int POWER_SAMPLE_ON_WAIT = 100;
|
||||
const int POWER_SAMPLE_OFF_WAIT = 1000;
|
||||
const int POWER_SAMPLE_OVERLOAD_WAIT = 20;
|
||||
|
||||
const int MIN_ACK_PULSE_DURATION = 3000;
|
||||
const int MIN_ACK_PULSE_DURATION = 2000;
|
||||
const int MAX_ACK_PULSE_DURATION = 8500;
|
||||
|
||||
|
||||
@ -45,8 +46,8 @@ const byte resetPacket[] = {0x00, 0x00, 0x00};
|
||||
|
||||
class DCCWaveform {
|
||||
public:
|
||||
DCCWaveform( byte preambleBits, bool isMain, int maxRawCurrent);
|
||||
static void begin();
|
||||
DCCWaveform( byte preambleBits, bool isMain);
|
||||
static void begin(MotorDriver * mainDriver, MotorDriver * progDriver);
|
||||
static void loop();
|
||||
static DCCWaveform mainTrack;
|
||||
static DCCWaveform progTrack;
|
||||
@ -73,7 +74,7 @@ class DCCWaveform {
|
||||
void setSignal(bool high);
|
||||
|
||||
bool isMainTrack;
|
||||
|
||||
MotorDriver* motorDriver;
|
||||
// Transmission controller
|
||||
byte transmitPacket[MAX_PACKET_SIZE]; // packet being transmitted
|
||||
byte transmitLength;
|
||||
@ -95,7 +96,6 @@ class DCCWaveform {
|
||||
POWERMODE powerMode;
|
||||
unsigned long lastSampleTaken;
|
||||
unsigned int sampleDelay;
|
||||
int rawCurrentTripValue;
|
||||
static const int ACK_CURRENT_TRIP=1000; // During ACK processing limit can be higher
|
||||
unsigned long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
|
||||
unsigned int power_good_counter = 0;
|
||||
|
124
Hardware.cpp
124
Hardware.cpp
@ -1,124 +0,0 @@
|
||||
/*
|
||||
* © 2020, Chris Harlow. All rights reserved.
|
||||
*
|
||||
* This file is part of Asbelos DCC API
|
||||
*
|
||||
* This is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* It 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
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
//#include <TimerOne.h> // use IDE menu Tools..Manage Libraries to locate and install TimerOne
|
||||
#include <ArduinoTimers.h> // use IDE menu Tools..Manage Libraries to locate and install TimerOne
|
||||
#include "AnalogReadFast.h"
|
||||
#include "Hardware.h"
|
||||
#include "Config.h"
|
||||
#include "DIAG.h"
|
||||
|
||||
|
||||
#if defined(ARDUINO_ARCH_AVR)
|
||||
#include <DIO2.h> // use IDE menu Tools..Manage Libraries to locate and install DIO2
|
||||
#define WritePin digitalWrite2
|
||||
#define ReadPin digitalRead2
|
||||
#else
|
||||
#define WritePin digitalWrite
|
||||
#define ReadPin digitalRead
|
||||
#endif
|
||||
|
||||
void Hardware::init() {
|
||||
pinMode(MAIN_POWER_PIN, OUTPUT);
|
||||
pinMode(MAIN_BRAKE_PIN, OUTPUT);
|
||||
pinMode(MAIN_SIGNAL_PIN, OUTPUT);
|
||||
if (MAIN_SIGNAL_PIN_ALT != UNUSED_PIN) pinMode(MAIN_SIGNAL_PIN_ALT, OUTPUT);
|
||||
pinMode(MAIN_SENSE_PIN, INPUT);
|
||||
if (MAIN_FAULT_PIN != UNUSED_PIN) pinMode(MAIN_FAULT_PIN, INPUT);
|
||||
|
||||
pinMode(PROG_POWER_PIN, OUTPUT);
|
||||
pinMode(PROG_BRAKE_PIN, OUTPUT);
|
||||
pinMode(PROG_SIGNAL_PIN, OUTPUT);
|
||||
if (PROG_SIGNAL_PIN_ALT != UNUSED_PIN) pinMode(PROG_SIGNAL_PIN_ALT, OUTPUT);
|
||||
pinMode(PROG_SENSE_PIN, INPUT);
|
||||
if (PROG_FAULT_PIN != UNUSED_PIN) pinMode(PROG_FAULT_PIN, INPUT);
|
||||
}
|
||||
|
||||
void Hardware::setPower(bool isMainTrack, bool on) {
|
||||
WritePin(isMainTrack ? MAIN_POWER_PIN : PROG_POWER_PIN, on ? HIGH : LOW);
|
||||
}
|
||||
void Hardware::setBrake(bool isMainTrack, bool on) {
|
||||
WritePin(isMainTrack ? MAIN_BRAKE_PIN : PROG_BRAKE_PIN, on ? HIGH : LOW);
|
||||
}
|
||||
|
||||
void Hardware::setSignal(bool isMainTrack, bool high) {
|
||||
byte pin = isMainTrack ? MAIN_SIGNAL_PIN : PROG_SIGNAL_PIN;
|
||||
byte pin2 = isMainTrack ? MAIN_SIGNAL_PIN_ALT : PROG_SIGNAL_PIN_ALT;
|
||||
WritePin(pin, high ? HIGH : LOW);
|
||||
if (pin2 != UNUSED_PIN) WritePin(pin2, high ? LOW : HIGH);
|
||||
}
|
||||
|
||||
void Hardware::setSyncSignal(bool high) {
|
||||
// This sets the same signal down both tracks at the same time.
|
||||
// Speed notes....
|
||||
// Objective is to get the two track signals to change as close as possible
|
||||
// the high ? HIGH:LOW will only be evaluated once
|
||||
// The UNUSED_PIN check will be done at compile time.
|
||||
// If even more speed is required, its possible (not SAMD) to pre-prepare the
|
||||
// DIO pinnumber->pincode translation so the WritePin (digitalWrite2) does not
|
||||
// have to calculate the register and bit numbers every time.
|
||||
|
||||
WritePin(MAIN_SIGNAL_PIN, high ? HIGH : LOW);
|
||||
WritePin(PROG_SIGNAL_PIN, high ? HIGH : LOW);
|
||||
if (MAIN_SIGNAL_PIN_ALT != UNUSED_PIN) WritePin(MAIN_SIGNAL_PIN_ALT, high ? LOW : HIGH);
|
||||
if (PROG_SIGNAL_PIN_ALT != UNUSED_PIN) WritePin(PROG_SIGNAL_PIN_ALT, high ? LOW : HIGH);
|
||||
}
|
||||
|
||||
int Hardware::getCurrentRaw(bool isMainTrack) {
|
||||
// tooo much crap for a interrupt routine. Will see how that goes.
|
||||
byte faultpin = isMainTrack ? MAIN_FAULT_PIN : PROG_FAULT_PIN;
|
||||
byte powerpin = isMainTrack ? MAIN_POWER_PIN : PROG_POWER_PIN;
|
||||
|
||||
if (faultpin != UNUSED_PIN && ReadPin(faultpin) == LOW && ReadPin(powerpin) == HIGH)
|
||||
return (int) (32000 / (isMainTrack ? MAIN_SENSE_FACTOR : PROG_SENSE_FACTOR)); // 32A should be enough
|
||||
// IMPORTANT: This function can be called in Interrupt() time within the 56uS timer
|
||||
// The default analogRead takes ~100uS which is catastrphic
|
||||
// so analogReadFast is used here. (-2uS)
|
||||
return analogReadFast(isMainTrack ? MAIN_SENSE_PIN : PROG_SENSE_PIN);
|
||||
|
||||
}
|
||||
|
||||
unsigned int Hardware::getCurrentMilliamps(bool isMainTrack, int raw) {
|
||||
return (unsigned int)(raw * (isMainTrack ? MAIN_SENSE_FACTOR : PROG_SENSE_FACTOR));
|
||||
}
|
||||
|
||||
void Hardware::setCallback(int duration, void (*isr)()) {
|
||||
TimerA.initialize();
|
||||
TimerA.setPeriod(duration);
|
||||
TimerA.attachInterrupt(isr);
|
||||
TimerA.start();
|
||||
}
|
||||
|
||||
// shortcut to cpu dependent high speed write
|
||||
void Hardware::pinWrite(int pin, bool high) {
|
||||
WritePin(pin,high);
|
||||
}
|
||||
|
||||
// Railcom support functions, not yet implemented
|
||||
//void Hardware::setSingleCallback(int duration, void (*isr)()) {
|
||||
// Timer2.initialize(duration);
|
||||
// Timer2.disablePwm(TIMER1_A_PIN);
|
||||
// Timer2.disablePwm(TIMER1_B_PIN);
|
||||
// Timer2.attachInterrupt(isr);
|
||||
//}
|
||||
|
||||
//void Hardware::resetSingleCallback(int duration) {
|
||||
// if (duration==0) Timer2.stop();
|
||||
// else Timer2.initialize(duration);
|
||||
//}
|
81
MotorDriver.cpp
Normal file
81
MotorDriver.cpp
Normal file
@ -0,0 +1,81 @@
|
||||
/*
|
||||
* © 2020, Chris Harlow. All rights reserved.
|
||||
*
|
||||
* This file is part of Asbelos DCC API
|
||||
*
|
||||
* This is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* It 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
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include "MotorDriver.h"
|
||||
#include "AnalogReadFast.h"
|
||||
#include "DIAG.h"
|
||||
|
||||
|
||||
|
||||
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_SAMC) || defined(ARDUINO_ARCH_MEGAAVR)
|
||||
#define WritePin digitalWrite
|
||||
#define ReadPin digitalRead
|
||||
#else
|
||||
// use the DIO2 libraray for much faster pin access
|
||||
#define GPIO2_PREFER_SPEED 1
|
||||
#include <DIO2.h> // use IDE menu Tools..Manage Libraries to locate and install DIO2
|
||||
#define WritePin digitalWrite2
|
||||
#define ReadPin digitalRead2
|
||||
#endif
|
||||
|
||||
MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin,
|
||||
byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) {
|
||||
powerPin=power_pin;
|
||||
signalPin=signal_pin;
|
||||
signalPin2=signal_pin2;
|
||||
brakePin=brake_pin;
|
||||
currentPin=current_pin;
|
||||
senseFactor=sense_factor;
|
||||
faultPin=fault_pin;
|
||||
tripMilliamps=trip_milliamps;
|
||||
rawCurrentTripValue=(int)(trip_milliamps / sense_factor);
|
||||
pinMode(powerPin, OUTPUT);
|
||||
pinMode(brakePin, OUTPUT);
|
||||
pinMode(signalPin, OUTPUT);
|
||||
if (signalPin2 != UNUSED_PIN) pinMode(signalPin2, OUTPUT);
|
||||
pinMode(currentPin, INPUT);
|
||||
if (faultPin != UNUSED_PIN) pinMode(faultPin, INPUT);
|
||||
}
|
||||
|
||||
void MotorDriver::setPower(bool on) {
|
||||
WritePin(powerPin, on ? HIGH : LOW);
|
||||
}
|
||||
void MotorDriver::setBrake( bool on) {
|
||||
WritePin(brakePin, on ? HIGH : LOW);
|
||||
}
|
||||
|
||||
void MotorDriver::setSignal( bool high) {
|
||||
WritePin(signalPin, high ? HIGH : LOW);
|
||||
if (signalPin2 != UNUSED_PIN) WritePin(signalPin2, high ? LOW : HIGH);
|
||||
}
|
||||
|
||||
|
||||
int MotorDriver::getCurrentRaw() {
|
||||
if (faultPin != UNUSED_PIN && ReadPin(faultPin) == LOW && ReadPin(powerPin) == HIGH)
|
||||
return (int)(32000/senseFactor);
|
||||
|
||||
// IMPORTANT: This function can be called in Interrupt() time within the 56uS timer
|
||||
// The default analogRead takes ~100uS which is catastrphic
|
||||
// so analogReadFast is used here. (-2uS)
|
||||
return analogReadFast(currentPin);
|
||||
}
|
||||
|
||||
unsigned int MotorDriver::convertToMilliamps( int raw) {
|
||||
return (unsigned int)(raw * senseFactor);
|
||||
}
|
@ -16,21 +16,24 @@
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#ifndef Hardware_h
|
||||
#define Hardware_h
|
||||
// Virtualised hardware Interface
|
||||
class Hardware {
|
||||
#ifndef MotorDriver_h
|
||||
#define MotorDriver_h
|
||||
// Virtualised Motor shield 1-track hardware Interface
|
||||
|
||||
class MotorDriver {
|
||||
public:
|
||||
static void init();
|
||||
static void setPower(bool isMainTrack, bool on);
|
||||
static void setSignal(bool isMainTrack, bool high);
|
||||
static void setSyncSignal( bool high);
|
||||
static unsigned int getCurrentMilliamps(bool isMainTrack, int rawValue);
|
||||
static int getCurrentRaw(bool isMainTrack);
|
||||
static void setBrake(bool isMainTrack, bool on);
|
||||
static void setCallback(int duration, void (*isr)());
|
||||
static void pinWrite(int pin, bool high); // gets better perf and less code than arduino digitalWrite
|
||||
// static void setSingleCallback(int duration, void (*isr)());
|
||||
// static void resetSingleCallback(int duration);
|
||||
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin, byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
|
||||
void setPower( bool on);
|
||||
void setSignal( bool high);
|
||||
void setBrake( bool on);
|
||||
int getCurrentRaw();
|
||||
unsigned int convertToMilliamps( int rawValue);
|
||||
|
||||
byte powerPin, signalPin, signalPin2, brakePin,currentPin,faultPin;
|
||||
float senseFactor;
|
||||
unsigned int tripMilliamps;
|
||||
int rawCurrentTripValue;
|
||||
const byte UNUSED_PIN = 255;
|
||||
|
||||
};
|
||||
#endif
|
@ -84,10 +84,10 @@ the state of any outputs being monitored or controlled by a separate interface o
|
||||
#include "Outputs.h"
|
||||
#include "EEStore.h"
|
||||
#include "StringFormatter.h"
|
||||
#include "Hardware.h"
|
||||
|
||||
void Output::activate(int s){
|
||||
data.oStatus=(s>0); // if s>0, set status to active, else inactive
|
||||
Hardware::pinWrite(data.pin,data.oStatus ^ bitRead(data.iFlag,0)); // set state of output pin to HIGH or LOW depending on whether bit zero of iFlag is set to 0 (ACTIVE=HIGH) or 1 (ACTIVE=LOW)
|
||||
digitalWrite(data.pin,data.oStatus ^ bitRead(data.iFlag,0)); // set state of output pin to HIGH or LOW depending on whether bit zero of iFlag is set to 0 (ACTIVE=HIGH) or 1 (ACTIVE=LOW)
|
||||
if(num>0)
|
||||
EEPROM.put(num,data.oStatus);
|
||||
|
||||
@ -146,7 +146,7 @@ void Output::load(){
|
||||
EEPROM.get(EEStore::pointer(),data);
|
||||
tt=create(data.id,data.pin,data.iFlag);
|
||||
tt->data.oStatus=bitRead(tt->data.iFlag,1)?bitRead(tt->data.iFlag,2):data.oStatus; // restore status to EEPROM value is bit 1 of iFlag=0, otherwise set to value of bit 2 of iFlag
|
||||
Hardware::pinWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
digitalWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
pinMode(tt->data.pin,OUTPUT);
|
||||
tt->num=EEStore::pointer();
|
||||
EEStore::advance(sizeof(tt->data));
|
||||
@ -195,7 +195,7 @@ Output *Output::create(int id, int pin, int iFlag, int v){
|
||||
|
||||
if(v==1){
|
||||
tt->data.oStatus=bitRead(tt->data.iFlag,1)?bitRead(tt->data.iFlag,2):0; // sets status to 0 (INACTIVE) is bit 1 of iFlag=0, otherwise set to value of bit 2 of iFlag
|
||||
Hardware::pinWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
digitalWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
pinMode(tt->data.pin,OUTPUT);
|
||||
}
|
||||
|
||||
|
@ -69,7 +69,7 @@ decide to ignore the <q ID> return and only react to <Q ID> triggers.
|
||||
#include "Sensors.h"
|
||||
#include "EEStore.h"
|
||||
#include "StringFormatter.h"
|
||||
#include "Hardware.h"
|
||||
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
@ -114,7 +114,7 @@ Sensor *Sensor::create(int snum, int pin, int pullUp){
|
||||
tt->active=false;
|
||||
tt->signal=1;
|
||||
pinMode(pin,INPUT); // set mode to input
|
||||
Hardware::pinWrite(pin,pullUp); // don't use Arduino's internal pull-up resistors for external infrared sensors --- each sensor must have its own 1K external pull-up resistor
|
||||
digitalWrite(pin,pullUp); // don't use Arduino's internal pull-up resistors for external infrared sensors --- each sensor must have its own 1K external pull-up resistor
|
||||
|
||||
return tt;
|
||||
|
||||
|
@ -26,6 +26,9 @@
|
||||
#define DIAGSERIAL SerialUSB
|
||||
#elif defined(ARDUINO_ARCH_AVR)
|
||||
#define DIAGSERIAL Serial
|
||||
#elif defined(ARDUINO_ARCH_MEGAAVR)
|
||||
#define DIAGSERIAL Serial
|
||||
#define __FlashStringHelper char
|
||||
#endif
|
||||
|
||||
class StringFormatter
|
||||
|
@ -19,7 +19,7 @@
|
||||
#include "Turnouts.h"
|
||||
#include "EEStore.h"
|
||||
#include "StringFormatter.h"
|
||||
#include "Hardware.h"
|
||||
|
||||
#include "PWMServoDriver.h"
|
||||
//#include "DIAG.h" // uncomment if you need DIAG below
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user