-
//Motors
const int limitleftpin = 3;
const int limitrightpin = 2;
const int motorpin2 = 4;
const int motorsenable = 6;
-unsigned int motorspeed = 77; // mm/s
+//DC motors
+const unsigned int rackwidth = 644; //mm
+unsigned int motorspeed = 77; // mm/s
//Servo motor
-const int servopin = 7;
+const int servopin = 7;
//buffer stuff
char command = 0;
-int value = 0;
+unsigned int value = 0;
#define POSITIVE 0
#define NEGATIVE 1
int sign = POSITIVE;
int a;
+unsigned int pos;
void eval(int command, int value)
{
Serial.println(F("LivingScreen"));
//Serial.flush();
break;
+ //relative translation
case 'T':
- Serial.print("Translate ");
- Serial.println(value);
+ //Serial.print("Translate ");
+ //Serial.println(value);
translate(value);
break;
+ //absolute movement
+ case 'M':
+ if (value != pos)
+ translate(value - pos);
+ break;
case 'R':
- Serial.print("Rotate ");
- Serial.println(value);
+ //Serial.print("Rotate ");
+ //Serial.println(value);
rotate(value);
break;
case 'A':
Serial.println(a);
break;
case 'C':
- Serial.println("Calibration");
+ //Serial.println("Calibration");
calibrate();
break;
case 'S':
Serial.print("Motor speed: ");
Serial.println(motorspeed);
break;
+ case 'P':
+ Serial.print("Position: ");
+ Serial.println(pos);
+ break;
+ case 'W':
+ Serial.print("Width: ");
+ Serial.println(rackwidth);
+ break;
default:
Serial.print("Unknown command ");
Serial.write(command);
#include <Servo.h>
-//DC motors
-const unsigned int rackwidth = 644; //mm
-
//Servo
Servo servo;
digitalWrite(motorpin2, LOW);
digitalWrite(motorsenable, LOW);
+
+ pos = rackwidth / 2;
}
{
if (!digitalRead(limitrightpin))
{
- Serial.println("Left limit reached");
- break;
+ //Serial.println("Left limit reached");
+ pos = rackwidth;
+ //motor stop
+ digitalWrite(motorpin1, LOW);
+ digitalWrite(motorpin2, LOW);
+
+ digitalWrite(motorsenable, LOW);
+ return;
}
delayMicroseconds(10);
}
{
if (!digitalRead(limitleftpin))
{
- Serial.println("Right limit reached");
- break;
+ //Serial.println("Right limit reached");
+ pos = 0;
+ //motor stop
+ digitalWrite(motorpin1, LOW);
+ digitalWrite(motorpin2, LOW);
+
+ digitalWrite(motorsenable, LOW);
+ return;
}
delayMicroseconds(10);
}
}
-
+
+ if (pos + distance < 0)
+ pos = 0;
+ else
+ pos += distance;
+
//motor stop
digitalWrite(motorpin1, LOW);
digitalWrite(motorpin2, LOW);