mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-27 01:56:14 +01:00
Compiled motorDriver
New motorDriver design...
This commit is contained in:
parent
ddc3917519
commit
cdcb01d300
|
@ -78,7 +78,13 @@ void setup() {
|
||||||
while(!DIAGSERIAL);
|
while(!DIAGSERIAL);
|
||||||
|
|
||||||
// Responsibility 2: Start the DCC engine.
|
// Responsibility 2: Start the DCC engine.
|
||||||
DCC::begin();
|
// 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(new MotorDriver(MAIN_POWER_PIN,MAIN_SIGNAL_PIN,MAIN_SIGNAL_PIN_ALT,MAIN_BRAKE_PIN,MAIN_SENSE_PIN,MAIN_SENSE_FACTOR, MAIN_MAX_MILLIAMPS,MAIN_FAULT_PIN),
|
||||||
|
new MotorDriver(PROG_POWER_PIN,PROG_SIGNAL_PIN,PROG_SIGNAL_PIN_ALT,PROG_BRAKE_PIN,PROG_SENSE_PIN,PROG_SENSE_FACTOR, PROG_MAX_MILLIAMPS,PROG_FAULT_PIN));
|
||||||
|
|
||||||
|
|
||||||
// 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
|
// NOTE: On a Uno you will have to provide a SoftwareSerial
|
||||||
|
|
6
DCC.cpp
6
DCC.cpp
|
@ -20,7 +20,7 @@
|
||||||
#include "DCC.h"
|
#include "DCC.h"
|
||||||
#include "DCCWaveform.h"
|
#include "DCCWaveform.h"
|
||||||
#include "DIAG.h"
|
#include "DIAG.h"
|
||||||
#include "Hardware.h"
|
|
||||||
|
|
||||||
// This module is responsible for converting API calls into
|
// This module is responsible for converting API calls into
|
||||||
// messages to be sent to the waveform generator.
|
// messages to be sent to the waveform generator.
|
||||||
|
@ -42,9 +42,9 @@ const byte FN_GROUP_4=0x08;
|
||||||
const byte FN_GROUP_5=0x10;
|
const byte FN_GROUP_5=0x10;
|
||||||
|
|
||||||
|
|
||||||
void DCC::begin() {
|
void DCC::begin(MotorDriver * mainDriver, MotorDriver* progDriver) {
|
||||||
debugMode=false;
|
debugMode=false;
|
||||||
DCCWaveform::begin();
|
DCCWaveform::begin(mainDriver,progDriver);
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) {
|
void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) {
|
||||||
|
|
3
DCC.h
3
DCC.h
|
@ -20,6 +20,7 @@
|
||||||
#define DCC_h
|
#define DCC_h
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
|
#include "MotorDriver.h"
|
||||||
|
|
||||||
typedef void (*ACK_CALLBACK)(int result);
|
typedef void (*ACK_CALLBACK)(int result);
|
||||||
|
|
||||||
|
@ -49,7 +50,7 @@ SKIPTARGET=0xFF // jump to target
|
||||||
class DCC {
|
class DCC {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
static void begin();
|
static void begin(MotorDriver * mainDriver, MotorDriver * progDriver);
|
||||||
static void loop();
|
static void loop();
|
||||||
|
|
||||||
// Public DCC API functions
|
// Public DCC API functions
|
||||||
|
|
|
@ -17,24 +17,22 @@
|
||||||
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "Hardware.h"
|
|
||||||
#include "DCCWaveform.h"
|
#include "DCCWaveform.h"
|
||||||
#include "DIAG.h"
|
#include "DIAG.h"
|
||||||
|
#include "MotorDriver.h"
|
||||||
#include <ArduinoTimers.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
|
||||||
|
|
||||||
|
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
|
||||||
DCCWaveform DCCWaveform::mainTrack=NULL;
|
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
|
||||||
DCCWaveform DCCWaveform::progTrack=NULL;
|
|
||||||
|
|
||||||
const int ACK_MIN_PULSE_RAW=65 / PROG_SENSE_FACTOR;
|
const int ACK_MIN_PULSE_RAW=65 / PROG_SENSE_FACTOR;
|
||||||
|
|
||||||
bool DCCWaveform::progTrackSyncMain=false;
|
bool DCCWaveform::progTrackSyncMain=false;
|
||||||
|
|
||||||
void DCCWaveform::begin(MotorDriver mainDriver, MotorDriver progDriver) {
|
void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
|
||||||
|
mainTrack.motorDriver=mainDriver;
|
||||||
mainTrack=new DCCWaveform(PREAMBLE_BITS_MAIN, true, mainDriver);
|
progTrack.motorDriver=progDriver;
|
||||||
progTrack=new DCCWaveform(PREAMBLE_BITS_PROG, false, progDriver);
|
|
||||||
progTrack.beginTrack(progDriver);
|
|
||||||
TimerA.initialize();
|
TimerA.initialize();
|
||||||
TimerA.setPeriod(58);
|
TimerA.setPeriod(58);
|
||||||
TimerA.attachInterrupt(interruptHandler);
|
TimerA.attachInterrupt(interruptHandler);
|
||||||
|
@ -73,10 +71,8 @@ void DCCWaveform::interruptHandler() {
|
||||||
const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
|
const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
|
||||||
|
|
||||||
|
|
||||||
DCCWaveform::DCCWaveform( byte preambleBits, bool isMain, MotorDriver driver) {
|
DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
|
||||||
// establish appropriate pins
|
// establish appropriate pins
|
||||||
motorDriver=driver;
|
|
||||||
rawCurrentTripValue=rawCurrentTrip;
|
|
||||||
isMainTrack = isMain;
|
isMainTrack = isMain;
|
||||||
packetPending = false;
|
packetPending = false;
|
||||||
memcpy(transmitPacket, idlePacket, sizeof(idlePacket));
|
memcpy(transmitPacket, idlePacket, sizeof(idlePacket));
|
||||||
|
@ -99,7 +95,7 @@ POWERMODE DCCWaveform::getPowerMode() {
|
||||||
void DCCWaveform::setPowerMode(POWERMODE mode) {
|
void DCCWaveform::setPowerMode(POWERMODE mode) {
|
||||||
powerMode = mode;
|
powerMode = mode;
|
||||||
bool ison = (mode == POWERMODE::ON);
|
bool ison = (mode == POWERMODE::ON);
|
||||||
driver.setPower( ison);
|
motorDriver->setPower( ison);
|
||||||
if (mode == POWERMODE::ON) delay(200);
|
if (mode == POWERMODE::ON) delay(200);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -108,7 +104,7 @@ void DCCWaveform::checkPowerOverload() {
|
||||||
|
|
||||||
if (millis() - lastSampleTaken < sampleDelay) return;
|
if (millis() - lastSampleTaken < sampleDelay) return;
|
||||||
lastSampleTaken = millis();
|
lastSampleTaken = millis();
|
||||||
int tripValue= driver.rawCurrentTripValue;
|
int tripValue= motorDriver->rawCurrentTripValue;
|
||||||
if (!isMainTrack && (ackPending || progTrackSyncMain)) tripValue=ACK_CURRENT_TRIP;
|
if (!isMainTrack && (ackPending || progTrackSyncMain)) tripValue=ACK_CURRENT_TRIP;
|
||||||
|
|
||||||
switch (powerMode) {
|
switch (powerMode) {
|
||||||
|
@ -117,7 +113,7 @@ void DCCWaveform::checkPowerOverload() {
|
||||||
break;
|
break;
|
||||||
case POWERMODE::ON:
|
case POWERMODE::ON:
|
||||||
// Check current
|
// Check current
|
||||||
lastCurrent = driver.getCurrentRaw();
|
lastCurrent = motorDriver->getCurrentRaw();
|
||||||
if (lastCurrent <= tripValue) {
|
if (lastCurrent <= tripValue) {
|
||||||
sampleDelay = POWER_SAMPLE_ON_WAIT;
|
sampleDelay = POWER_SAMPLE_ON_WAIT;
|
||||||
if(power_good_counter<100)
|
if(power_good_counter<100)
|
||||||
|
@ -126,8 +122,8 @@ void DCCWaveform::checkPowerOverload() {
|
||||||
if (power_sample_overload_wait>POWER_SAMPLE_OVERLOAD_WAIT) power_sample_overload_wait=POWER_SAMPLE_OVERLOAD_WAIT;
|
if (power_sample_overload_wait>POWER_SAMPLE_OVERLOAD_WAIT) power_sample_overload_wait=POWER_SAMPLE_OVERLOAD_WAIT;
|
||||||
} else {
|
} else {
|
||||||
setPowerMode(POWERMODE::OVERLOAD);
|
setPowerMode(POWERMODE::OVERLOAD);
|
||||||
unsigned int mA=driver.convertRawToMilliamps(lastCurrent);
|
unsigned int mA=motorDriver->convertToMilliamps(lastCurrent);
|
||||||
unsigned int maxmA=driver.convertRawToMilliamps(tripValue);
|
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);
|
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;
|
power_good_counter=0;
|
||||||
sampleDelay = power_sample_overload_wait;
|
sampleDelay = power_sample_overload_wait;
|
||||||
|
@ -187,11 +183,11 @@ void DCCWaveform::setSignal(bool high) {
|
||||||
if (progTrackSyncMain) {
|
if (progTrackSyncMain) {
|
||||||
if (!isMainTrack) return; // ignore PROG track waveform while in sync
|
if (!isMainTrack) return; // ignore PROG track waveform while in sync
|
||||||
// set both tracks to same signal
|
// set both tracks to same signal
|
||||||
driver.setSyncSignal(high);
|
motorDriver->setSignal(high);
|
||||||
progTrack.driver.setSignal(high);
|
progTrack.motorDriver->setSignal(high);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
driver.setSignal(high);
|
motorDriver->setSignal(high);
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCWaveform::interrupt2() {
|
void DCCWaveform::interrupt2() {
|
||||||
|
@ -269,8 +265,8 @@ int DCCWaveform::getLastCurrent() {
|
||||||
|
|
||||||
void DCCWaveform::setAckBaseline(bool debug) {
|
void DCCWaveform::setAckBaseline(bool debug) {
|
||||||
if (isMainTrack) return;
|
if (isMainTrack) return;
|
||||||
ackThreshold=driver.getCurrentRaw() + ACK_MIN_PULSE_RAW;
|
ackThreshold=motorDriver->getCurrentRaw() + ACK_MIN_PULSE_RAW;
|
||||||
if (debug) DIAG(F("\nACK-BASELINE %d/%dmA"),ackThreshold,driver.convertRawToMilliamps(ackThreshold));
|
if (debug) DIAG(F("\nACK-BASELINE %d/%dmA"),ackThreshold,motorDriver->convertToMilliamps(ackThreshold));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DCCWaveform::setAckPending(bool debug) {
|
void DCCWaveform::setAckPending(bool debug) {
|
||||||
|
@ -287,7 +283,7 @@ void DCCWaveform::setAckPending(bool debug) {
|
||||||
byte DCCWaveform::getAck(bool debug) {
|
byte DCCWaveform::getAck(bool debug) {
|
||||||
if (ackPending) return (2); // still waiting
|
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,
|
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
|
if (ackDetected) return (1); // Yes we had an ack
|
||||||
return(0); // pending set off but not detected means no ACK.
|
return(0); // pending set off but not detected means no ACK.
|
||||||
}
|
}
|
||||||
|
@ -301,7 +297,7 @@ void DCCWaveform::checkAck() {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
lastCurrent=Hardware::getCurrentRaw(false);
|
lastCurrent=motorDriver->getCurrentRaw();
|
||||||
if (lastCurrent > ackMaxCurrent) ackMaxCurrent=lastCurrent;
|
if (lastCurrent > ackMaxCurrent) ackMaxCurrent=lastCurrent;
|
||||||
// An ACK is a pulse lasting between MIN_ACK_PULSE_DURATION and MAX_ACK_PULSE_DURATION uSecs (refer @haba)
|
// An ACK is a pulse lasting between MIN_ACK_PULSE_DURATION and MAX_ACK_PULSE_DURATION uSecs (refer @haba)
|
||||||
|
|
||||||
|
|
|
@ -19,6 +19,7 @@
|
||||||
#ifndef DCCWaveform_h
|
#ifndef DCCWaveform_h
|
||||||
#define DCCWaveform_h
|
#define DCCWaveform_h
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
|
#include "MotorDriver.h"
|
||||||
|
|
||||||
const int POWER_SAMPLE_ON_WAIT = 100;
|
const int POWER_SAMPLE_ON_WAIT = 100;
|
||||||
const int POWER_SAMPLE_OFF_WAIT = 1000;
|
const int POWER_SAMPLE_OFF_WAIT = 1000;
|
||||||
|
@ -45,8 +46,8 @@ const byte resetPacket[] = {0x00, 0x00, 0x00};
|
||||||
|
|
||||||
class DCCWaveform {
|
class DCCWaveform {
|
||||||
public:
|
public:
|
||||||
DCCWaveform( byte preambleBits, bool isMain, int maxRawCurrent);
|
DCCWaveform( byte preambleBits, bool isMain);
|
||||||
static void begin();
|
static void begin(MotorDriver * mainDriver, MotorDriver * progDriver);
|
||||||
static void loop();
|
static void loop();
|
||||||
static DCCWaveform mainTrack;
|
static DCCWaveform mainTrack;
|
||||||
static DCCWaveform progTrack;
|
static DCCWaveform progTrack;
|
||||||
|
@ -73,7 +74,7 @@ class DCCWaveform {
|
||||||
void setSignal(bool high);
|
void setSignal(bool high);
|
||||||
|
|
||||||
bool isMainTrack;
|
bool isMainTrack;
|
||||||
|
MotorDriver* motorDriver;
|
||||||
// Transmission controller
|
// Transmission controller
|
||||||
byte transmitPacket[MAX_PACKET_SIZE]; // packet being transmitted
|
byte transmitPacket[MAX_PACKET_SIZE]; // packet being transmitted
|
||||||
byte transmitLength;
|
byte transmitLength;
|
||||||
|
@ -95,7 +96,6 @@ class DCCWaveform {
|
||||||
POWERMODE powerMode;
|
POWERMODE powerMode;
|
||||||
unsigned long lastSampleTaken;
|
unsigned long lastSampleTaken;
|
||||||
unsigned int sampleDelay;
|
unsigned int sampleDelay;
|
||||||
int rawCurrentTripValue;
|
|
||||||
static const int ACK_CURRENT_TRIP=1000; // During ACK processing limit can be higher
|
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 long power_sample_overload_wait = POWER_SAMPLE_OVERLOAD_WAIT;
|
||||||
unsigned int power_good_counter = 0;
|
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);
|
|
||||||
//}
|
|
36
Hardware.h
36
Hardware.h
|
@ -1,36 +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/>.
|
|
||||||
*/
|
|
||||||
#ifndef Hardware_h
|
|
||||||
#define Hardware_h
|
|
||||||
// Virtualised hardware Interface
|
|
||||||
class Hardware {
|
|
||||||
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);
|
|
||||||
};
|
|
||||||
#endif
|
|
|
@ -31,7 +31,8 @@
|
||||||
#define ReadPin digitalRead
|
#define ReadPin digitalRead
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
MotorDriver::MotorDriver(byte power_pin, int signal_pin, int signal_pin2, int brake_pin, int current_pin, float sense_factor, int fault_pin) {
|
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;
|
powerPin=power_pin;
|
||||||
signalPin=signal_pin;
|
signalPin=signal_pin;
|
||||||
signalPin2=signal_pin2;
|
signalPin2=signal_pin2;
|
||||||
|
@ -39,8 +40,8 @@ MotorDriver::MotorDriver(byte power_pin, int signal_pin, int signal_pin2, int br
|
||||||
currentPin=current_pin;
|
currentPin=current_pin;
|
||||||
senseFactor=sense_factor;
|
senseFactor=sense_factor;
|
||||||
faultPin=fault_pin;
|
faultPin=fault_pin;
|
||||||
I32=(int) (32000 / sensefactor);
|
tripMilliamps=trip_milliamps;
|
||||||
|
rawCurrentTripValue=(int)(trip_milliamps / sense_factor);
|
||||||
pinMode(powerPin, OUTPUT);
|
pinMode(powerPin, OUTPUT);
|
||||||
pinMode(brakePin, OUTPUT);
|
pinMode(brakePin, OUTPUT);
|
||||||
pinMode(signalPin, OUTPUT);
|
pinMode(signalPin, OUTPUT);
|
||||||
|
@ -64,14 +65,14 @@ void MotorDriver::setSignal( bool high) {
|
||||||
|
|
||||||
int MotorDriver::getCurrentRaw() {
|
int MotorDriver::getCurrentRaw() {
|
||||||
if (faultPin != UNUSED_PIN && ReadPin(faultPin) == LOW && ReadPin(powerPin) == HIGH)
|
if (faultPin != UNUSED_PIN && ReadPin(faultPin) == LOW && ReadPin(powerPin) == HIGH)
|
||||||
return I32:
|
return (int)(32000/senseFactor);
|
||||||
|
|
||||||
// IMPORTANT: This function can be called in Interrupt() time within the 56uS timer
|
// IMPORTANT: This function can be called in Interrupt() time within the 56uS timer
|
||||||
// The default analogRead takes ~100uS which is catastrphic
|
// The default analogRead takes ~100uS which is catastrphic
|
||||||
// so analogReadFast is used here. (-2uS)
|
// so analogReadFast is used here. (-2uS)
|
||||||
return analogReadFast(sensePin);
|
return analogReadFast(currentPin);
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned int MortorDriver::convertRawToMilliamps( int raw) {
|
unsigned int MotorDriver::convertToMilliamps( int raw) {
|
||||||
return (unsigned int)(raw * senseFactor);
|
return (unsigned int)(raw * senseFactor);
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,17 +19,21 @@
|
||||||
#ifndef MotorDriver_h
|
#ifndef MotorDriver_h
|
||||||
#define MotorDriver_h
|
#define MotorDriver_h
|
||||||
// Virtualised Motor shield 1-track hardware Interface
|
// Virtualised Motor shield 1-track hardware Interface
|
||||||
|
|
||||||
class MotorDriver {
|
class MotorDriver {
|
||||||
public:
|
public:
|
||||||
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin, byte current_pin, float senseFactor, byte faultPin);
|
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 setPower( bool on);
|
||||||
void setSignal( bool high);
|
void setSignal( bool high);
|
||||||
void setBrake( bool on);
|
void setBrake( bool on);
|
||||||
int getCurrentRaw();
|
int getCurrentRaw();
|
||||||
unsigned int convertToMilliamps( int rawValue);
|
unsigned int convertToMilliamps( int rawValue);
|
||||||
private:
|
|
||||||
byte powerPin, signalPin, signalPin2, brakePin,currentPin,faultPin;
|
byte powerPin, signalPin, signalPin2, brakePin,currentPin,faultPin;
|
||||||
float senseFactor;
|
float senseFactor;
|
||||||
|
unsigned int tripMilliamps;
|
||||||
|
int rawCurrentTripValue;
|
||||||
|
const byte UNUSED_PIN = 255;
|
||||||
|
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -84,10 +84,10 @@ the state of any outputs being monitored or controlled by a separate interface o
|
||||||
#include "Outputs.h"
|
#include "Outputs.h"
|
||||||
#include "EEStore.h"
|
#include "EEStore.h"
|
||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
#include "Hardware.h"
|
|
||||||
void Output::activate(int s){
|
void Output::activate(int s){
|
||||||
data.oStatus=(s>0); // if s>0, set status to active, else inactive
|
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)
|
if(num>0)
|
||||||
EEPROM.put(num,data.oStatus);
|
EEPROM.put(num,data.oStatus);
|
||||||
|
|
||||||
|
@ -146,7 +146,7 @@ void Output::load(){
|
||||||
EEPROM.get(EEStore::pointer(),data);
|
EEPROM.get(EEStore::pointer(),data);
|
||||||
tt=create(data.id,data.pin,data.iFlag);
|
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
|
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);
|
pinMode(tt->data.pin,OUTPUT);
|
||||||
tt->num=EEStore::pointer();
|
tt->num=EEStore::pointer();
|
||||||
EEStore::advance(sizeof(tt->data));
|
EEStore::advance(sizeof(tt->data));
|
||||||
|
@ -195,7 +195,7 @@ Output *Output::create(int id, int pin, int iFlag, int v){
|
||||||
|
|
||||||
if(v==1){
|
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
|
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);
|
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 "Sensors.h"
|
||||||
#include "EEStore.h"
|
#include "EEStore.h"
|
||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
#include "Hardware.h"
|
|
||||||
|
|
||||||
///////////////////////////////////////////////////////////////////////////////
|
///////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
@ -114,7 +114,7 @@ Sensor *Sensor::create(int snum, int pin, int pullUp){
|
||||||
tt->active=false;
|
tt->active=false;
|
||||||
tt->signal=1;
|
tt->signal=1;
|
||||||
pinMode(pin,INPUT); // set mode to input
|
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;
|
return tt;
|
||||||
|
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
#include "Turnouts.h"
|
#include "Turnouts.h"
|
||||||
#include "EEStore.h"
|
#include "EEStore.h"
|
||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
#include "Hardware.h"
|
|
||||||
#include "PWMServoDriver.h"
|
#include "PWMServoDriver.h"
|
||||||
//#include "DIAG.h" // uncomment if you need DIAG below
|
//#include "DIAG.h" // uncomment if you need DIAG below
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue
Block a user