Merge pull request #37 from TimEvWw/master

Pin Guard
pull/39/head
Tim Evers 2016-05-16 19:09:22 +02:00
commit 6a9f87a115
11 changed files with 326 additions and 31 deletions

View File

@ -99,6 +99,27 @@ const long ENCODER_MISSED_STEPS_DECAY_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT = 10;
// pin guard default settings
const long PIN_GUARD_1_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_1_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_1_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_2_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_2_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_2_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_3_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_3_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_3_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_4_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_4_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_4_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_5_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_5_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_5_ACTIVE_STATE_DEFAULT = 1;
const long STATUS_GENERAL_DEFAULT = 0;

View File

@ -2,7 +2,7 @@
#include <EEPROM.h>
static ParameterList* instanceParam;
int paramValues[150];
int paramValues[PARAM_NR_OF_PARAMS];
ParameterList * ParameterList::getInstance() {
if (!instanceParam) {
@ -73,14 +73,30 @@ int ParameterList::writeValue(int id, int value) {
Serial.print(value);
Serial.print("\n");
// If any value is written,
// trigger the loading of the new configuration in all other modules
sendConfigToModules();
return 0;
}
void ParameterList::sendConfigToModules() {
// Trigger other modules to load the new values
PinGuard::getInstance()->loadConfig();
}
int ParameterList::readAllValues() {
Serial.print("R99");
Serial.print(" ");
Serial.print("reading all values");
Serial.print("\n");
// Make a dump of all values
// Check if it's a valid value to keep the junk out of the list
for (int i; i < 150; i++)
for (int i; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i)) {
readValue(i);
@ -126,7 +142,7 @@ int ParameterList::writeValueEeprom(int id, int value) {
int ParameterList::readAllValuesFromEeprom() {
// Write all existing values to eeprom
for (int i; i < 150; i++)
for (int i; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i)) {
paramValues[i] = readValueEeprom(i);
@ -149,7 +165,7 @@ int ParameterList::writeAllValuesToEeprom() {
int ParameterList::setAllValuesToDefault() {
// Copy default values to the memory values
for (int i; i < 150; i++)
for (int i; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i)) {
loadDefaultValue(i);
@ -204,6 +220,27 @@ void ParameterList::loadDefaultValue(int id) {
case ENCODER_MISSED_STEPS_DECAY_Y : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT; break;
case ENCODER_MISSED_STEPS_DECAY_Z : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT; break;
case PIN_GUARD_1_PIN_NR : paramValues[id] = PIN_GUARD_1_PIN_NR_DEFAULT; break;
case PIN_GUARD_1_TIME_OUT : paramValues[id] = PIN_GUARD_1_TIME_OUT_DEFAULT; break;
case PIN_GUARD_1_ACTIVE_STATE : paramValues[id] = PIN_GUARD_1_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_2_PIN_NR : paramValues[id] = PIN_GUARD_2_PIN_NR_DEFAULT; break;
case PIN_GUARD_2_TIME_OUT : paramValues[id] = PIN_GUARD_2_TIME_OUT_DEFAULT; break;
case PIN_GUARD_2_ACTIVE_STATE : paramValues[id] = PIN_GUARD_2_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_3_PIN_NR : paramValues[id] = PIN_GUARD_3_PIN_NR_DEFAULT; break;
case PIN_GUARD_3_TIME_OUT : paramValues[id] = PIN_GUARD_3_TIME_OUT_DEFAULT; break;
case PIN_GUARD_3_ACTIVE_STATE : paramValues[id] = PIN_GUARD_3_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_4_PIN_NR : paramValues[id] = PIN_GUARD_4_PIN_NR_DEFAULT; break;
case PIN_GUARD_4_TIME_OUT : paramValues[id] = PIN_GUARD_4_TIME_OUT_DEFAULT; break;
case PIN_GUARD_4_ACTIVE_STATE : paramValues[id] = PIN_GUARD_4_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_5_PIN_NR : paramValues[id] = PIN_GUARD_5_PIN_NR_DEFAULT; break;
case PIN_GUARD_5_TIME_OUT : paramValues[id] = PIN_GUARD_5_TIME_OUT_DEFAULT; break;
case PIN_GUARD_5_ACTIVE_STATE : paramValues[id] = PIN_GUARD_5_ACTIVE_STATE_DEFAULT; break;
default : paramValues[id] = 0; break;
}
}
@ -244,6 +281,21 @@ bool ParameterList::validParam(int id) {
case ENCODER_MISSED_STEPS_DECAY_X:
case ENCODER_MISSED_STEPS_DECAY_Y:
case ENCODER_MISSED_STEPS_DECAY_Z:
case PIN_GUARD_1_PIN_NR:
case PIN_GUARD_1_TIME_OUT:
case PIN_GUARD_1_ACTIVE_STATE:
case PIN_GUARD_2_PIN_NR:
case PIN_GUARD_2_TIME_OUT:
case PIN_GUARD_2_ACTIVE_STATE:
case PIN_GUARD_3_PIN_NR:
case PIN_GUARD_3_TIME_OUT:
case PIN_GUARD_3_ACTIVE_STATE:
case PIN_GUARD_4_PIN_NR:
case PIN_GUARD_4_TIME_OUT:
case PIN_GUARD_4_ACTIVE_STATE:
case PIN_GUARD_5_PIN_NR:
case PIN_GUARD_5_TIME_OUT:
case PIN_GUARD_5_ACTIVE_STATE:
return true;
default:
return false;

View File

@ -3,9 +3,11 @@
#include "Arduino.h"
#include "Config.h"
#include "PinGuard.h"
//#define NULL 0
const int PARAM_NR_OF_PARAMS = 300;
enum ParamListEnum
@ -59,7 +61,29 @@ enum ParamListEnum
// not used in software at this time
MOVEMENT_AXIS_NR_STEPS_X = 141,
MOVEMENT_AXIS_NR_STEPS_Y = 142,
MOVEMENT_AXIS_NR_STEPS_Z = 143
MOVEMENT_AXIS_NR_STEPS_Z = 143,
// pin guard settings
PIN_GUARD_1_PIN_NR = 201,
PIN_GUARD_1_TIME_OUT = 202,
PIN_GUARD_1_ACTIVE_STATE = 203,
PIN_GUARD_2_PIN_NR = 205,
PIN_GUARD_2_TIME_OUT = 206,
PIN_GUARD_2_ACTIVE_STATE = 207,
PIN_GUARD_3_PIN_NR = 211,
PIN_GUARD_3_TIME_OUT = 212,
PIN_GUARD_3_ACTIVE_STATE = 213,
PIN_GUARD_4_PIN_NR = 215,
PIN_GUARD_4_TIME_OUT = 216,
PIN_GUARD_4_ACTIVE_STATE = 217,
PIN_GUARD_5_PIN_NR = 221,
PIN_GUARD_5_TIME_OUT = 222,
PIN_GUARD_5_ACTIVE_STATE = 223
};
@ -85,6 +109,9 @@ public:
int readValueEeprom(int id);
int writeValueEeprom(int id, int value);
void sendConfigToModules();
private:
ParameterList();
ParameterList(ParameterList const&);

View File

@ -36,7 +36,7 @@ int PinControl::readValue(int pinNr, int mode) {
int value = 0;
if (mode == 0) {
if (digitalRead(pinNr) == 0){
if (digitalRead(pinNr) == 1){
value = 1;
}
}

39
src/PinGuard.cpp 100644
View File

@ -0,0 +1,39 @@
#include "PinGuard.h"
static PinGuard* instance;
PinGuard * PinGuard::getInstance() {
if (!instance) {
instance = new PinGuard();
};
return instance;
}
;
PinGuard::PinGuard() {
pinGuardPin[0] = PinGuardPin();
pinGuardPin[1] = PinGuardPin();
pinGuardPin[2] = PinGuardPin();
pinGuardPin[3] = PinGuardPin();
pinGuardPin[4] = PinGuardPin();
loadConfig();
}
void PinGuard::loadConfig() {
pinGuardPin[0].loadPinConfig(PIN_GUARD_1_PIN_NR, PIN_GUARD_1_ACTIVE_STATE, PIN_GUARD_1_TIME_OUT);
pinGuardPin[1].loadPinConfig(PIN_GUARD_2_PIN_NR, PIN_GUARD_2_ACTIVE_STATE, PIN_GUARD_2_TIME_OUT);
pinGuardPin[2].loadPinConfig(PIN_GUARD_3_PIN_NR, PIN_GUARD_3_ACTIVE_STATE, PIN_GUARD_3_TIME_OUT);
pinGuardPin[3].loadPinConfig(PIN_GUARD_4_PIN_NR, PIN_GUARD_4_ACTIVE_STATE, PIN_GUARD_4_TIME_OUT);
pinGuardPin[4].loadPinConfig(PIN_GUARD_5_PIN_NR, PIN_GUARD_5_ACTIVE_STATE, PIN_GUARD_5_TIME_OUT);
}
void PinGuard::checkPins() {
pinGuardPin[0].processTick();
pinGuardPin[1].processTick();
pinGuardPin[2].processTick();
pinGuardPin[3].processTick();
pinGuardPin[4].processTick();
}

43
src/PinGuard.h 100644
View File

@ -0,0 +1,43 @@
/*
* PinGuard.h
*
* Created on: 2016-03-13
* Author: Tim Evers
*/
#ifndef PINGUARD_H_
#define PINGUARD_H_
#include "Arduino.h"
#include "pins.h"
#include "Config.h"
#include <stdio.h>
#include <stdlib.h>
#include "PinGuardPin.h"
#include "ParameterList.h"
class PinGuard {
public:
static PinGuard* getInstance();
void loadConfig();
void checkPins();
private:
//long pinTimeOut[100];
//long pinCurrentTime[100];
//void checkPin;
//bool pinSafeState[100];
PinGuardPin pinGuardPin[5];
//PinGuardPin test;
PinGuard();
PinGuard(PinGuard const&);
void operator=(PinGuard const&);
};
#endif /* PINGUARD_H_ */

View File

@ -0,0 +1,38 @@
#include "PinGuardPin.h"
PinGuardPin::PinGuardPin() {
pinNr = 0;
}
// Set the initial settings for what pin to check
void PinGuardPin::loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr) {
pinNr = ParameterList::getInstance()->getValue(pinNrParamNr);
activeState = (ParameterList::getInstance()->getValue(activeStateParamNr)== 1);
timeOut = ParameterList::getInstance()->getValue(timeOutParamNr);
timeOutCount = 0;
}
// Check each second if the time out is lapsed or the value has changed
void PinGuardPin::processTick() {
if (pinNr==0) {
return;
}
currentStatePin = digitalRead(pinNr);
if (currentStatePin != activeState) {
timeOutCount = 0;
} else {
timeOutCount++;
}
if (timeOutCount >= timeOut) {
digitalWrite(pinNr, !activeState);
}
}

38
src/PinGuardPin.h 100644
View File

@ -0,0 +1,38 @@
/*
* PinGuardPin.h
*
* Created on: 2016-04-02
* Author: Tim Evers
*/
#ifndef PINGUARDPIN_H_
#define PINGUARDPIN_H_
#include "Arduino.h"
#include "pins.h"
#include "Config.h"
#include <stdio.h>
#include <stdlib.h>
#include "ParameterList.h"
class PinGuardPin {
public:
PinGuardPin();
void processTick();
void loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr);
private:
//PinControlPin(PinControlPin const&);
///void operator=(PinControlPin const&);
int pinNr;
long timeOut;
long timeOutCount;
bool activeState;
bool currentStatePin;
};
#endif /* PINGUARDPIN_H_ */

View File

@ -1,5 +1,4 @@
#include "StepperControl.h"
#include "TimerOne.h"
static StepperControl* instance;
@ -101,8 +100,6 @@ StepperControl::StepperControl() {
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B);
encoderZ.loadPinNumbers(Z_ENCDR_A, Z_ENCDR_B);
Timer1.start();
}
void StepperControl::test() {
@ -887,16 +884,6 @@ void StepperControl::checkAxisVsEncoder(StepperControlAxis* axis, StepperControl
}
}
bool interruptBusy = false;
void handleMovementInterruptTest(void) {
if (interruptBusy == false) {
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
//blinkLed();
interruptBusy = false;
}
}
void StepperControl::loadMotorSettings() {
// Load settings
@ -974,13 +961,6 @@ void StepperControl::loadEncoderSettings() {
}
}
// Start the interrupt used for moviing
// Interrupt management code library written by Paul Stoffregen
void StepperControl::initInterrupt() {
Timer1.attachInterrupt(handleMovementInterruptTest);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
}
unsigned long StepperControl::getMaxLength(unsigned long lengths[3]) {
unsigned long max = lengths[0];
for (int i = 1; i < 3; i++) {

View File

@ -4,6 +4,8 @@
#include "Config.h"
#include "StepperControl.h"
#include "ServoControl.h"
#include "PinGuard.h"
#include "TimerOne.h"
static char commandEndChar = 0x0A;
static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
@ -11,8 +13,44 @@ static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
unsigned long lastAction;
unsigned long currentTime;
// Blink led routine used for testing
bool blink = false;
void blinkLed() {
blink = !blink;
digitalWrite(LED_PIN,blink);
}
// Interrupt handling for:
// - movement
// - encoders
// - pin guard
//
bool interruptBusy = false;
int interruptSecondTimer = 0;
void interrupt(void) {
interruptSecondTimer++;
if (interruptBusy == false) {
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
// Check the actions triggered once per second
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED) {
interruptSecondTimer = 0;
PinGuard::getInstance()->checkPins();
//blinkLed();
}
interruptBusy = false;
}
}
//The setup function is called once at startup of the sketch
void setup() {
// Setup pin input/output settings
pinMode(X_STEP_PIN , OUTPUT);
pinMode(X_DIR_PIN , OUTPUT);
pinMode(X_ENABLE_PIN, OUTPUT);
@ -45,19 +83,29 @@ void setup() {
Serial.begin(115200);
// Start the motor handling
ServoControl::getInstance()->attach();
StepperControl::getInstance()->initInterrupt();
//StepperControl::getInstance()->startTimer();
// Dump all values to the serial interface
ParameterList::getInstance()->readAllValues();
// Get the settings for the pin guard
PinGuard::getInstance()->loadConfig();
// Start the interrupt used for moviing
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
// Initialize the inactivity check
lastAction = millis();
}
// The loop function is called in an endless loop
void loop() {
if (Serial.available()) {
String commandString = Serial.readStringUntil(commandEndChar);
@ -88,7 +136,10 @@ void loop() {
if ((currentTime - lastAction) > 5000) {
// After an idle time, send the idle message
Serial.print("R00\r\n");
CurrentState::getInstance()->printPosition();
CurrentState::getInstance()->printEndStops();
lastAction = millis();
}
}
}

View File

@ -7,6 +7,8 @@
#define X_MAX_PIN 2
#define X_ENCDR_A 16
#define X_ENCDR_B 17
#define X_ENCDR_A_Q 31
#define X_ENCDR_B_Q 33
#define Y_STEP_PIN 60
#define Y_DIR_PIN 61
@ -15,6 +17,8 @@
#define Y_MAX_PIN 15
#define Y_ENCDR_A 23
#define Y_ENCDR_B 25
#define Y_ENCDR_A_Q 35
#define Y_ENCDR_B_Q 37
#define Z_STEP_PIN 46
#define Z_DIR_PIN 48
@ -23,6 +27,8 @@
#define Z_MAX_PIN 19
#define Z_ENCDR_A 27
#define Z_ENCDR_B 29
#define Z_ENCDR_A_Q 39
#define Z_ENCDR_B_Q 41
#define E_STEP_PIN 26
#define E_DIR_PIN 28