mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-12-23 21:01:25 +01:00
Save memory
by eliminating last call to arduino version of digitalRead
This commit is contained in:
parent
8d4d9bd28e
commit
57cc5ad705
12
Hardware.cpp
12
Hardware.cpp
@ -66,10 +66,10 @@ void Hardware::setSignal(bool isMainTrack, bool 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 signalpin = isMainTrack ? MAIN_SIGNAL_PIN : PROG_SIGNAL_PIN;
|
||||
byte powerpin = isMainTrack ? MAIN_POWER_PIN : PROG_POWER_PIN;
|
||||
|
||||
if (faultpin != UNUSED_PIN && ReadPin(faultpin) == LOW && ReadPin(signalpin) == HIGH)
|
||||
return 32767; // MAXINT because we don't know the actual current, return as high as we can
|
||||
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)
|
||||
@ -78,7 +78,7 @@ int Hardware::getCurrentRaw(bool isMainTrack) {
|
||||
}
|
||||
|
||||
unsigned int Hardware::getCurrentMilliamps(bool isMainTrack, int raw) {
|
||||
return (int)(raw * (isMainTrack ? MAIN_SENSE_FACTOR : PROG_SENSE_FACTOR));
|
||||
return (unsigned int)(raw * (isMainTrack ? MAIN_SENSE_FACTOR : PROG_SENSE_FACTOR));
|
||||
}
|
||||
|
||||
void Hardware::setCallback(int duration, void (*isr)()) {
|
||||
@ -89,6 +89,10 @@ void Hardware::setCallback(int duration, void (*isr)()) {
|
||||
Timer1.attachInterrupt(isr);
|
||||
}
|
||||
|
||||
// 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)()) {
|
||||
|
@ -28,6 +28,7 @@ class Hardware {
|
||||
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);
|
||||
};
|
||||
|
@ -84,9 +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
|
||||
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)
|
||||
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)
|
||||
if(num>0)
|
||||
EEPROM.put(num,data.oStatus);
|
||||
|
||||
@ -145,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
|
||||
digitalWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
Hardware::pinWrite(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));
|
||||
@ -194,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
|
||||
digitalWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
Hardware::pinWrite(tt->data.pin,tt->data.oStatus ^ bitRead(tt->data.iFlag,0));
|
||||
pinMode(tt->data.pin,OUTPUT);
|
||||
}
|
||||
|
||||
|
@ -69,6 +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"
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
@ -113,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
|
||||
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
|
||||
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
|
||||
|
||||
return tt;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user