Compare commits
No commits in common. "1aca2dd5c0cf94f4a58aba1e7ba1fa2787cc7d64" and "0dc3269b31dfe6f894f5f111f19421f5c379591d" have entirely different histories.
1aca2dd5c0
...
0dc3269b31
|
@ -1 +1 @@
|
|||
0.2.1
|
||||
0.2.0
|
|
@ -7,77 +7,65 @@ ContactPrinter::ContactPrinter () {
|
|||
|
||||
void ContactPrinter::Setup () {
|
||||
|
||||
pinMode(takeup_pin_dir_a, OUTPUT);
|
||||
pinMode(takeup_pin_dir_b, OUTPUT);
|
||||
pinMode(takeup_picture_pin_cw, OUTPUT);
|
||||
pinMode(takeup_picture_pin_ccw, OUTPUT);
|
||||
pinMode(takeup_stock_pin_cw, OUTPUT);
|
||||
pinMode(takeup_stock_pin_ccw, OUTPUT);
|
||||
|
||||
pinMode(start_button_pin, INPUT_PULLUP);
|
||||
|
||||
drive_motor.Setup();
|
||||
|
||||
ledcSetup(takeup_pwm_channel, pwm_frequency, pwm_resolution);
|
||||
Serial.print("Attaching pin ");
|
||||
Serial.print(takeup_pin_enable);
|
||||
Serial.print(" to ledc channel ");
|
||||
Serial.print(takeup_pwm_channel);
|
||||
Serial.println(" for takeup");
|
||||
ledcAttachPin(takeup_pin_enable, takeup_pwm_channel);
|
||||
ledcWrite(takeup_pwm_channel, takeup_pwm_duty_cycle);
|
||||
ledcSetup(takeup_picture_pwm_channel, pwm_frequency, pwm_resolution);
|
||||
ledcSetup(takeup_stock_pwm_channel, pwm_frequency, pwm_resolution);
|
||||
|
||||
digitalWrite(takeup_pin_dir_a, LOW);
|
||||
digitalWrite(takeup_pin_dir_b, LOW);
|
||||
ledcAttachPin(takeup_picture_pin_enable, takeup_picture_pwm_channel);
|
||||
ledcAttachPin(takeup_stock_pin_enable, takeup_stock_pwm_channel);
|
||||
|
||||
SetDirectionTakeup(true);
|
||||
SetSpeedTakeup(0.9);
|
||||
SetSpeedDrive(0.8);
|
||||
start_time = millis();
|
||||
ledcWrite(takeup_picture_pwm_channel, takeup_pwm_duty_cycle);
|
||||
ledcWrite(takeup_stock_pwm_channel, takeup_pwm_duty_cycle);
|
||||
|
||||
digitalWrite(takeup_picture_pin_cw, LOW);
|
||||
digitalWrite(takeup_picture_pin_ccw, LOW);
|
||||
digitalWrite(takeup_stock_pin_cw, LOW);
|
||||
digitalWrite(takeup_stock_pin_ccw, LOW);
|
||||
|
||||
SetSpeedTakeup(0.4);
|
||||
SetSpeedDrive(1.0);
|
||||
}
|
||||
|
||||
void ContactPrinter::Start () {
|
||||
Serial.println("Start()");
|
||||
drive_motor.Start();
|
||||
StartTakeup();
|
||||
run_time = timer;
|
||||
//RampTakeup(0, takeup_pwm_duty_cycle, takeup_ramp_time);
|
||||
|
||||
running = true;
|
||||
}
|
||||
|
||||
void ContactPrinter::Stop () {
|
||||
Serial.println("Stop()");
|
||||
drive_motor.Stop();
|
||||
StopTakeup();
|
||||
run_time = timer;
|
||||
running = false;
|
||||
RampTakeup(takeup_pwm_duty_cycle, 0, takeup_ramp_time);
|
||||
digitalWrite(takeup_picture_pin_cw, LOW);
|
||||
digitalWrite(takeup_picture_pin_ccw, LOW);
|
||||
digitalWrite(takeup_stock_pin_cw, LOW);
|
||||
digitalWrite(takeup_stock_pin_ccw, LOW);
|
||||
}
|
||||
|
||||
void ContactPrinter::SetSpeedTakeup(float speed) {
|
||||
takeup_speed = speed;
|
||||
takeup_pwm_duty_cycle = floor(speed * pwm_maximum);
|
||||
Serial.print("Set takeup motors PWM = ");
|
||||
Serial.println(takeup_pwm_duty_cycle);
|
||||
}
|
||||
|
||||
void ContactPrinter::StartTakeup () {
|
||||
ledcWrite(takeup_pwm_channel, takeup_pwm_duty_cycle);
|
||||
if (takeup_dir) {
|
||||
digitalWrite(takeup_pin_dir_a, LOW);
|
||||
digitalWrite(takeup_pin_dir_b, HIGH);
|
||||
} else {
|
||||
digitalWrite(takeup_pin_dir_a, HIGH);
|
||||
digitalWrite(takeup_pin_dir_b, LOW);
|
||||
}
|
||||
}
|
||||
|
||||
void ContactPrinter::StopTakeup() {
|
||||
digitalWrite(takeup_pin_dir_a, LOW);
|
||||
digitalWrite(takeup_pin_dir_b, LOW);
|
||||
ledcWrite(takeup_pwm_channel, 0);
|
||||
takeup_pwm_duty_cycle = floor(speed * 255);
|
||||
}
|
||||
|
||||
void ContactPrinter::SetSpeedDrive(float speed) {
|
||||
drive_motor.SetSpeed(speed);
|
||||
}
|
||||
|
||||
void ContactPrinter::SetDirectionTakeup(bool dir) {
|
||||
takeup_dir = dir;
|
||||
void ContactPrinter::SetDirectionStock(bool clockwise) {
|
||||
takeup_stock_cw = clockwise;
|
||||
}
|
||||
|
||||
void ContactPrinter::SetDirectionPicture(bool clockwise) {
|
||||
takeup_picture_cw = clockwise;
|
||||
}
|
||||
|
||||
//linear
|
||||
|
@ -89,11 +77,28 @@ void ContactPrinter::RampTakeup(uint16_t start_pwm, uint16_t end_pwm, uint16_t t
|
|||
takeup_ramp_current_step = 0;
|
||||
takeup_ramping = true;
|
||||
|
||||
if (takeup_picture_cw) {
|
||||
digitalWrite(takeup_picture_pin_cw, HIGH);
|
||||
digitalWrite(takeup_picture_pin_ccw, LOW);
|
||||
} else {
|
||||
digitalWrite(takeup_picture_pin_cw, LOW);
|
||||
digitalWrite(takeup_picture_pin_ccw, HIGH);
|
||||
}
|
||||
if (takeup_stock_cw) {
|
||||
digitalWrite(takeup_stock_pin_cw, HIGH);
|
||||
digitalWrite(takeup_stock_pin_ccw, LOW);
|
||||
} else {
|
||||
digitalWrite(takeup_stock_pin_cw, LOW);
|
||||
digitalWrite(takeup_stock_pin_ccw, HIGH);
|
||||
}
|
||||
|
||||
for (uint16_t i = 0; i < takeup_ramp_steps; i++) {
|
||||
if (takeup_pwm_duty_cycle <= 0 || takeup_pwm_duty_cycle >= pwm_maximum) {
|
||||
if (takeup_pwm_duty_cycle <= 0 || takeup_pwm_duty_cycle >= 255) {
|
||||
takeup_ramping = false;
|
||||
break;
|
||||
}
|
||||
ledcWrite(takeup_pwm_channel, takeup_pwm_duty_cycle);
|
||||
ledcWrite(takeup_picture_pwm_channel, takeup_pwm_duty_cycle);
|
||||
ledcWrite(takeup_stock_pwm_channel, takeup_pwm_duty_cycle);
|
||||
delay(takeup_ramp_step);
|
||||
if (takeup_ramp_dir) {
|
||||
takeup_pwm_duty_cycle++;
|
||||
|
@ -104,12 +109,13 @@ void ContactPrinter::RampTakeup(uint16_t start_pwm, uint16_t end_pwm, uint16_t t
|
|||
takeup_ramping = false;
|
||||
}
|
||||
|
||||
void ContactPrinter::RampTakeupLoop () {
|
||||
|
||||
}
|
||||
|
||||
void ContactPrinter::ButtonLoop () {
|
||||
if (!running && timer >= run_time + button_delay && digitalRead(start_button_pin) == LOW) {
|
||||
if (!running && digitalRead(start_button_pin) == LOW) {
|
||||
Start();
|
||||
} else if (running && timer >= run_time + button_delay && digitalRead(start_button_pin) == LOW) {
|
||||
Stop();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -119,13 +125,11 @@ bool ContactPrinter::IsRunning () {
|
|||
|
||||
void ContactPrinter::Loop () {
|
||||
timer = millis();
|
||||
if (initialized) {
|
||||
ButtonLoop();
|
||||
if (running) {
|
||||
drive_motor.Loop();
|
||||
}
|
||||
} else if (timer >= start_time + 100) {
|
||||
initialized = true;
|
||||
if (takeup_ramping) {
|
||||
RampTakeupLoop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -17,26 +17,25 @@ class ContactPrinter {
|
|||
const uint16_t baud = 115200;
|
||||
|
||||
/* PINS */
|
||||
const uint8_t takeup_pin_enable = 21;
|
||||
const uint8_t takeup_pin_dir_a = 22;
|
||||
const uint8_t takeup_pin_dir_b = 23;
|
||||
const uint8_t takeup_picture_pin_enable = 23;
|
||||
const uint8_t takeup_picture_pin_cw = 22;
|
||||
const uint8_t takeup_picture_pin_ccw = 21;
|
||||
|
||||
const uint8_t takeup_stock_pin_enable = 19;
|
||||
const uint8_t takeup_stock_pin_cw = 18;
|
||||
const uint8_t takeup_stock_pin_ccw = 5;
|
||||
|
||||
const uint8_t start_button_pin = 15;
|
||||
|
||||
/* MOTOR PWM */
|
||||
const uint32_t pwm_frequency = 5000;
|
||||
const uint8_t takeup_pwm_channel = 1;
|
||||
const uint32_t pwm_frequency = 30000;
|
||||
const uint8_t takeup_picture_pwm_channel = 1;
|
||||
const uint8_t takeup_stock_pwm_channel = 2;
|
||||
const uint8_t pwm_resolution = 8;
|
||||
const uint16_t pwm_maximum = 255; //8 = 255, 16 = 65535
|
||||
|
||||
/* BUTTONS */
|
||||
const uint16_t button_delay = 500;
|
||||
|
||||
/* MEMORY */
|
||||
|
||||
volatile long timer = 0;
|
||||
volatile long start_time = 0;
|
||||
volatile long run_time = 0;
|
||||
|
||||
volatile float drive_speed = 1.0; //calculated rpm
|
||||
volatile float takeup_speed = 1.0; //estimated rpm
|
||||
|
@ -53,9 +52,12 @@ class ContactPrinter {
|
|||
|
||||
volatile boolean takeup_ramping = false;
|
||||
|
||||
volatile bool takeup_dir = true;
|
||||
volatile bool takeup_picture_cw = false;
|
||||
volatile bool takeup_picture_ccw = true;
|
||||
|
||||
volatile bool takeup_stock_cw = true;
|
||||
volatile bool takeup_stock_ccw = true;
|
||||
|
||||
volatile bool initialized = false;
|
||||
volatile bool running = false;
|
||||
|
||||
public:
|
||||
|
@ -68,11 +70,8 @@ class ContactPrinter {
|
|||
void Stop();
|
||||
void SetSpeedTakeup(float speed);
|
||||
void SetSpeedDrive(float speed);
|
||||
void SetDirectionTakeup(bool dir);
|
||||
|
||||
void StartTakeup();
|
||||
void StopTakeup();
|
||||
void EnableTakeup();
|
||||
void SetDirectionStock(bool clockwise);
|
||||
void SetDirectionPicture(bool clockwise);
|
||||
|
||||
void RampTakeup(uint16_t start, uint16_t end, uint16_t time);
|
||||
void RampTakeupLoop();
|
||||
|
|
|
@ -21,11 +21,6 @@ void DriveMotor::Setup () {
|
|||
pinMode(encoder_b_pin, INPUT);
|
||||
|
||||
ledcSetup(pwm_channel, pwm_frequency, pwm_resolution);
|
||||
Serial.print("Attaching pin ");
|
||||
Serial.print(enable_pin);
|
||||
Serial.print(" to ledc channel ");
|
||||
Serial.print(pwm_channel);
|
||||
Serial.println(" for drive");
|
||||
ledcAttachPin(enable_pin, pwm_channel);
|
||||
ledcWrite(pwm_channel, pwm_duty_cycle);
|
||||
|
||||
|
@ -39,14 +34,15 @@ void DriveMotor::Start() {
|
|||
digitalWrite(backward_pin, LOW);
|
||||
}
|
||||
|
||||
void DriveMotor::Stop() {;
|
||||
void DriveMotor::Stop() {
|
||||
pwm_duty_cycle = 0;
|
||||
digitalWrite(forward_pin, LOW);
|
||||
digitalWrite(backward_pin, LOW);
|
||||
ledcWrite(pwm_channel, 0);
|
||||
ledcWrite(pwm_channel, pwm_duty_cycle);
|
||||
}
|
||||
|
||||
void DriveMotor::SetSpeed(float speed) {
|
||||
pwm_duty_cycle = floor(pwm_maximum * speed);
|
||||
pwm_duty_cycle = floor(255 * speed);
|
||||
Serial.print("Set drive motor PWM = ");
|
||||
Serial.println(pwm_duty_cycle);
|
||||
}
|
||||
|
|
|
@ -16,10 +16,9 @@ class DriveMotor {
|
|||
|
||||
volatile uint8_t pwm_duty_cycle = 0;
|
||||
|
||||
const uint32_t pwm_frequency = 5000;
|
||||
const uint32_t pwm_frequency = 30000;
|
||||
const uint8_t pwm_channel = 0;
|
||||
const uint8_t pwm_resolution = 8;
|
||||
const uint16_t pwm_maximum = 255; //8 = 255, 16 = 65535
|
||||
|
||||
const uint8_t ppr = 11;
|
||||
const float ratio = 187.0 / 3.0;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#include "ContactPrinter.h";
|
||||
|
||||
#define VERSION "0"
|
||||
#define VERSION "0.2.0"
|
||||
|
||||
/**
|
||||
*
|
||||
|
@ -9,19 +9,23 @@
|
|||
*
|
||||
* Pins
|
||||
*
|
||||
* 21 Takeup Picture Enable - set duty rate
|
||||
* 22 Takeup Direction A - Stock Clockwise, Picture Counter Clockwise
|
||||
* 23 Takeup Direction B - Stock Counter Clockwise, Picture Clockwise
|
||||
* 23 Takeup Picture Enable - set duty rate
|
||||
* 22 Takeup Picture Clockwise
|
||||
* 21 Takeup Picture Counter Clockwise
|
||||
*
|
||||
* 26 Drive Enable
|
||||
* 27 Drive Forward (Clockwise)
|
||||
* 19 Takeup Stock Enable - set duty rate
|
||||
* 18 Takeup Stock Clockwise
|
||||
* 5 Takeup Stock Counter Clockwise
|
||||
*
|
||||
* 13 Drive Enable
|
||||
* 12 Drive Forward (Clockwise)
|
||||
* 14 Drive Backward (Counter Clockwise)
|
||||
* 33 Drive Encoder A
|
||||
* 25 Drive Encoder B
|
||||
* 27 Drive Encoder A
|
||||
* 26 Drive Encoder B
|
||||
*
|
||||
* 15 Start Button
|
||||
*
|
||||
* 32 Lamp
|
||||
* 33 Lamp
|
||||
*
|
||||
**/
|
||||
|
||||
|
@ -29,9 +33,9 @@ ContactPrinter contact_printer;
|
|||
|
||||
void setup () {
|
||||
Serial.begin(115200);
|
||||
contact_printer.Setup();
|
||||
Serial.print("contact_printer v");
|
||||
Serial.println(VERSION);
|
||||
contact_printer.Setup();
|
||||
}
|
||||
void loop () {
|
||||
contact_printer.Loop();
|
||||
|
|
|
@ -6,14 +6,9 @@
|
|||
*********/
|
||||
|
||||
// Motor A
|
||||
//int motor1Pin1 = 14;
|
||||
//int motor1Pin2 = 27;
|
||||
//int enable1Pin = 26;
|
||||
|
||||
// Motor B
|
||||
int motor1Pin1 = 5;
|
||||
int motor1Pin2 = 18;
|
||||
int enable1Pin = 19;
|
||||
int motor1Pin1 = 14;
|
||||
int motor1Pin2 = 27;
|
||||
int enable1Pin = 26;
|
||||
|
||||
// Setting PWM properties
|
||||
const int freq = 30000;
|
||||
|
|
|
@ -15,7 +15,7 @@ if [[ "${1}" == "major" ]]; then
|
|||
elif [[ "${1}" == "minor" ]]; then
|
||||
let "VERSION[1]=${VERSION[1]}+1"
|
||||
let "VERSION[2]=0"
|
||||
else
|
||||
else; then
|
||||
let "VERSION[2]=${VERSION[2]}+1"
|
||||
fi
|
||||
|
||||
|
|
Loading…
Reference in New Issue