mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-22 23:56:13 +01:00
Merge branch 'master' into Ethernewt-
This commit is contained in:
commit
b1ac7feb01
|
@ -34,19 +34,20 @@
|
|||
#define ReadPin digitalRead2
|
||||
#endif
|
||||
|
||||
MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin,
|
||||
MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t 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);
|
||||
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(brakePin < 0 ? -brakePin : brakePin, OUTPUT);
|
||||
setBrake(false);
|
||||
pinMode(signalPin, OUTPUT);
|
||||
if (signalPin2 != UNUSED_PIN) pinMode(signalPin2, OUTPUT);
|
||||
pinMode(currentPin, INPUT);
|
||||
|
@ -54,10 +55,32 @@ MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte
|
|||
}
|
||||
|
||||
void MotorDriver::setPower(bool on) {
|
||||
if (brakePin == -4 && on) {
|
||||
// toggle brake before turning power on - resets overcurrent error
|
||||
// on the Pololu board if brake is wired to ^D2.
|
||||
setBrake(true);
|
||||
setBrake(false);
|
||||
}
|
||||
WritePin(powerPin, on ? HIGH : LOW);
|
||||
}
|
||||
void MotorDriver::setBrake( bool on) {
|
||||
WritePin(brakePin, on ? HIGH : LOW);
|
||||
|
||||
// setBrake applies brake if on == true. So to get
|
||||
// voltage from the motor bride one needs to do a
|
||||
// setBrake(false).
|
||||
// If the brakePin is negative that means the sense
|
||||
// of the brake pin on the motor bridge is inverted
|
||||
// (HIGH == release brake) and setBrake does
|
||||
// compensate for that.
|
||||
//
|
||||
void MotorDriver::setBrake(bool on) {
|
||||
bool state = on;
|
||||
byte pin = brakePin;
|
||||
if (brakePin < 0) {
|
||||
pin=-pin;
|
||||
state=!state;
|
||||
}
|
||||
WritePin(pin, state ? HIGH : LOW);
|
||||
//DIAG(F("BrakePin: %d is %d\n"), pin, ReadPin(pin));
|
||||
}
|
||||
|
||||
void MotorDriver::setSignal( bool high) {
|
||||
|
|
|
@ -20,9 +20,13 @@
|
|||
#define MotorDriver_h
|
||||
// Virtualised Motor shield 1-track hardware Interface
|
||||
|
||||
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
|
||||
#define UNUSED_PIN 127 // inside int8_t
|
||||
#endif
|
||||
|
||||
class MotorDriver {
|
||||
public:
|
||||
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin, byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
|
||||
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin, byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
|
||||
virtual void setPower( bool on);
|
||||
virtual void setSignal( bool high);
|
||||
virtual void setBrake( bool on);
|
||||
|
@ -34,11 +38,10 @@ class MotorDriver {
|
|||
}
|
||||
|
||||
private:
|
||||
byte powerPin, signalPin, signalPin2, brakePin,currentPin,faultPin;
|
||||
byte powerPin, signalPin, signalPin2, currentPin, faultPin;
|
||||
int8_t brakePin; // negative means pin is inverted
|
||||
float senseFactor;
|
||||
unsigned int tripMilliamps;
|
||||
int rawCurrentTripValue;
|
||||
const byte UNUSED_PIN = 255;
|
||||
|
||||
};
|
||||
#endif
|
||||
|
|
|
@ -13,10 +13,16 @@
|
|||
// similar to those defined here, WITHOUT editing this file. You can put your
|
||||
// custom defines in config.h.
|
||||
|
||||
const byte UNUSED_PIN = 255;
|
||||
#ifndef UNUSED_PIN // sync define with the one in MotorDriver.h
|
||||
#define UNUSED_PIN 127 // inside int8_t
|
||||
#endif
|
||||
|
||||
// MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, byte brake_pin, byte current_pin,
|
||||
// MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin, byte current_pin,
|
||||
// float senseFactor, unsigned int tripMilliamps, byte faultPin);
|
||||
//
|
||||
// If the brakePin is negative that means the sense
|
||||
// of the brake pin on the motor bridge is inverted
|
||||
// (HIGH == release brake)
|
||||
|
||||
// Arduino standard Motor Shield
|
||||
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
||||
|
@ -24,9 +30,19 @@ const byte UNUSED_PIN = 255;
|
|||
new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
|
||||
|
||||
// Pololu Motor Shield
|
||||
#define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \
|
||||
new MotorDriver(4, 7, UNUSED_PIN, 9, A0, 18, 3000, 12), \
|
||||
new MotorDriver(2, 8, UNUSED_PIN, 10, A1, 18, 3000, UNUSED_PIN)
|
||||
#define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \
|
||||
new MotorDriver( 9, 7, UNUSED_PIN, -4, A0, 18, 3000, 12), \
|
||||
new MotorDriver(10, 8, UNUSED_PIN, UNUSED_PIN, A1, 18, 3000, UNUSED_PIN)
|
||||
//
|
||||
// Actually, on the Pololu MC33926 shield the enable lines are tied together on pin 4 and the
|
||||
// pins 9 and 10 work as "inverted brake" but as we turn on and off the tracks individually
|
||||
// via the power pins we above use 9 and 10 as power pins and 4 as "inverted brake" which in this
|
||||
// version of the code always will be high. That means this config is not usable for generating
|
||||
// a railcom cuotout in the future. For that one must wire the second ^D2 to pin 2 and define
|
||||
// the motor driver like this:
|
||||
// new MotorDriver(4, 7, UNUSED_PIN, -9, A0, 18, 3000, 12)
|
||||
// new MotorDriver(2, 8, UNUSED_PIN, -10, A1, 18, 3000, UNUSED_PIN)
|
||||
// See Pololu dial_mc33926_shield_schematic.pdf and truth table on page 17 of the MC33926 data sheet.
|
||||
|
||||
// Firebox Mk1
|
||||
#define FIREBOX_MK1 F("FIREBOX_MK1"), \
|
||||
|
|
Loading…
Reference in New Issue
Block a user