// int MotorA = 3;
// int MotorB = 5;
// int IN1 = 6;
// int IN2 = 9;
// int IN3 = 10;
// int IN4 = 11;
// int speed = 255;
// void setup()
// {
// pinMode(IN1, OUTPUT);
// pinMode(IN2, OUTPUT);
// pinMode(IN3, OUTPUT);
// pinMode(IN4, OUTPUT);
// pinMode(MotorA, OUTPUT);
// pinMode(MotorB, OUTPUT);
// Serial.begin(9600);
// }
// void loop()
// {
// Serial.println('up');
// goUP();
// Serial.println('down');
// goDOWN();
// }
// void goDOWN(){
// analogWrite(MotorA, speed);
// analogWrite(MotorB, speed);
// delay(50);
// digitalWrite(IN1, HIGH);
// digitalWrite(IN3, HIGH);
// delay(1000);
// analogWrite(MotorA, LOW);
// digitalWrite(IN1, LOW);
// analogWrite(MotorB, LOW);
// digitalWrite(IN3, LOW);
// }
// void goUP(){
// analogWrite(MotorA, speed);
// analogWrite(MotorB, speed);
// delay(50);
// digitalWrite(IN2, HIGH);
// digitalWrite(IN4, HIGH);
// delay(1000+up_delay(1000));
// analogWrite(MotorA, LOW);
// digitalWrite(IN2, LOW);
// analogWrite(MotorB, LOW);
// digitalWrite(IN4, LOW);
// }
// int up_delay(int total_time){
// return total_time / 7;
// }
#include "MyStepper.h"
#include <Servo.h>
// Pins
#define PEN_SERVO_PIN 7
#define STEPPER_ENABLE_PIN A1
#define MotorA 3
#define MotorB 5
#define IN1 6
#define IN2 9
#define IN3 10
#define IN4 11
// Stepper steps per revolution
#define STEPS 48
// Rensponse codes
#define RESP_OK 'Y'
#define RESP_KO 'N'
// Motors
MyStepper leftStepper(STEPS, IN1, IN2, MotorA);
MyStepper rightStepper(STEPS, IN3, IN4, MotorB);
Servo penServo;
// Steppers speeds
#define INITIAL_STEPPERS_SPEED 255
int fastStepperSpeed = 255;
int slowStepperSpeed = 140;
// Pen servo positions
int penWritePosition = 50;
int penUpPosition = 70;
#define PEN_DAMPING_DELAY 7
int oldPenPosition = penUpPosition;
long leftStepperPosition = 0L,
rightStepperPosition = 0L,
oldLeftStepperPosition = 0L,
oldRightStepperPosition = 0L;
int pendelay = 10;
boolean pen = false;
boolean oldpen = false;
void setup()
{
Serial.begin(9600);
pinMode(IN1, OUTPUT);
pinMode(IN2, OUTPUT);
pinMode(IN3, OUTPUT);
pinMode(IN4, OUTPUT);
pinMode(STEPPER_ENABLE_PIN, OUTPUT);
digitalWrite(STEPPER_ENABLE_PIN, HIGH);
setSteppersSpeed(INITIAL_STEPPERS_SPEED);
penServo.attach(PEN_SERVO_PIN);
setPenPosition(penWritePosition);
}
void loop()
{
// setPenPosition(penWritePosition);
// delay(1000);
// setPenPosition(penUpPosition);
// delay(1000);
//----------------------------------
/*
should go down and stay down
*/
// leftStepper.step(20);
// rightStepper.step(20);
// leftStepper.step(-20);
// rightStepper.step(-20);
// ----------------------------------
/*
the following piece of code is a adapted from the 3 command ( move down )
*/
// Serial.println("start");
// setSteppersSpeed(fastStepperSpeed);
// pen = false;
// moveSteppers(20, -20);
// Serial.println("moveSteppers");
// if (oldpen != pen){
// delay(pendelay);
// Serial.println("delaying");
// }
// oldpen = pen;
// Serial.println("done");
// delay(2000);
//----------------------------------
/*
moving to coordinates
*/
// moveToCoordinates(10,10);
// delay(1000);
// moveToCoordinates(-20,-20);
// delay(1000);
//----------------------------------
/*
moving to coordinates v2
*/
// moveToCoordinates(-30,0);
// moveToCoordinates(30,0);
// oldLeftStepperPosition = leftStepperPosition;
// oldRightStepperPosition = rightStepperPosition;
//----------------------------------
/*
the fucking goHome function
*/
// moveToCoordinates(5,0);
// delay(1000);
// moveToCoordinates(0,5);
// delay(1000);
// moveToCoordinates(-5,0);
// delay(1000);
// moveToCoordinates(0,-5);
// delay(1000);
//----------------------------------
/*
this is the serial event.
*/
oldLeftStepperPosition = leftStepperPosition;
oldRightStepperPosition = rightStepperPosition;
receiveCommand();
}
/////////////////////////////////////////////////////////////////////////////////////////////////////RECEIVE COMMAND
void receiveCommand()
{
while (Serial.available() > 0)
{
int commandCode = Serial.parseInt();
float commandParam1 = Serial.parseFloat();
float commandParam2 = Serial.parseFloat();
if (Serial.read() == '\n')
{
if (executeCommand(commandCode, commandParam1, commandParam2))
Serial.println(RESP_OK);
else
Serial.println(RESP_KO);
}
}
}
/////////////////////////////////////////////////////////////////////////////////////////////////////EXECUTE COMMAND
boolean executeCommand (int commandCode, float commandParam1, float commandParam2)
{
if (commandCode == 0)
{
// Move, no write, fast speed
setSteppersSpeed(fastStepperSpeed);
pen = false;
setPenPosition(penUpPosition);
if (oldpen != pen)
delay(pendelay);
oldpen = pen;
moveToCoordinates(commandParam1, commandParam2);
return true;
}
else if (commandCode == 1)
{
// Write while moving, slow speed
setSteppersSpeed(slowStepperSpeed);
pen = true;
setPenPosition(penWritePosition);
if (oldpen != pen)
delay(pendelay);
oldpen = pen;
moveToCoordinates(commandParam1, commandParam2);
return true;
}
else if (commandCode == 2)
{
// Move the steppers and write. fast speed
setSteppersSpeed(fastStepperSpeed);
pen = false;
setPenPosition(penWritePosition);
moveSteppers(commandParam1, commandParam2);
if (oldpen != pen)
delay(pendelay);
oldpen = pen;
return true;
}
else if (commandCode == 3)
{
// Move the steppers, no write, fast speed
setSteppersSpeed(fastStepperSpeed);
pen = false;
//setPenPosition(penUpPosition);
moveSteppers(commandParam1, commandParam2);
if (oldpen != pen)
delay(pendelay);
oldpen = pen;
return true;
}
else if (commandCode == 4)
{
// Move the steppers and write. fast speed
setSteppersSpeed(fastStepperSpeed);
pen = true;
setPenPosition(penWritePosition);
moveSteppers(commandParam1, commandParam2);
if (oldpen != pen)
delay(pendelay);
oldpen = pen;
return true;
}
else if (commandCode == 5)
setPenPosition(penUpPosition);
else if (commandCode == 6)
{
// Initial calibration, no move
leftStepperPosition = commandParam1;
rightStepperPosition = commandParam2;
return true;
}
else if (commandCode == 7)
{
// Set slow and fast speed values
fastStepperSpeed = commandParam1;
slowStepperSpeed = commandParam2;
return true;
}
else if (commandCode == 9)
{
// Set pen servo position
setPenPosition(commandParam1);
return true;
}
else if (commandCode == 10)
{
// Set pen up servo position
penUpPosition = commandParam1;
return true;
}
else if (commandCode == 11)
{
// Set pen write servo position
penWritePosition = commandParam1;
return true;
}
else if (commandCode == 20)
{
// Disable stepper motors
digitalWrite(STEPPER_ENABLE_PIN, LOW);
return true;
}
else if (commandCode == 21)
{
// Enable stepper motors
digitalWrite(STEPPER_ENABLE_PIN, HIGH);
return true;
}
else
{
// Unrecognized command
return false;
}
}
//MOVE TO COORDINATES
void moveToCoordinates (long newLeftStepperPosition, long newRightStepperPosition)
{
leftStepperPosition = newLeftStepperPosition;
rightStepperPosition = newRightStepperPosition;
long distLEFT = max(leftStepperPosition, oldLeftStepperPosition) - min(leftStepperPosition, oldLeftStepperPosition);
if (leftStepperPosition < oldLeftStepperPosition)
distLEFT = -distLEFT;
long distRIGHT = max(rightStepperPosition, oldRightStepperPosition) - min(rightStepperPosition, oldRightStepperPosition);
if (rightStepperPosition < oldRightStepperPosition)
distRIGHT = -distRIGHT;
moveAlongLine(0L, 0L, distLEFT, distRIGHT);
delay(10);
}
//MOVE ALONG LINE
// thanks to http://arduino.cc/forum/index.php/topic,65835.msg482379.html#msg482379
void moveAlongLine (long x0, long y0, long x1, long y1)
{
// Bresenham's Line Algorithm
long ox, oy;
int ma, mb;
long dx = abs(x1 - x0), sx = x0 < x1 ? 1 : -1;
long dy = abs(y1 - y0), sy = y0 < y1 ? 1 : -1;
long err = (dx > dy ? dx : -dy) / 2, e2;
for(;;)
{
ox = x0;
oy = y0;
if (x0 == x1 && y0 == y1)
break;
e2 = err;
if (e2 > -dx)
{
err -= dy;
x0 += sx;
}
if (e2 < dy)
{
err += dx;
y0 += sy;
}
ma = mb = 0;
if (y0 < oy)
{
mb = -6;
}
if (y0 > oy)
{
mb = 6;
}
if (x0 < ox)
{
ma = -6;
}
if (x0 > ox)
{
ma = 6;
}
moveSteppers(ma, mb);
delay(100);
}
}
/////////////////////////////////////////////////////////////////////////////////////////////////////MOVE STEPPERS
void moveSteppers (int leftSteps, int rightSteps)
{
leftStepper.step(leftSteps);
rightStepper.step(rightSteps);
}
/////////////////////////////////////////////////////////////////////////////////////////////////////SET STEPPERS SPEED
void setSteppersSpeed (int steppersSpeed)
{
leftStepper.setSpeed(steppersSpeed);
rightStepper.setSpeed(steppersSpeed);
}
void setPenPosition (int penPosition)
{
if (penPosition > oldPenPosition)
{
for (int i = oldPenPosition; i < penPosition; ++i)
{
penServo.write(i);
delay(PEN_DAMPING_DELAY);
}
oldPenPosition = penPosition;
}
else if (penPosition < oldPenPosition)
{
for (int i = oldPenPosition; i > penPosition; --i)
{
penServo.write(i);
delay(PEN_DAMPING_DELAY);
}
oldPenPosition = penPosition;
}
}
Comments
Please log in or sign up to comment.