A manual controller for a spindle motor

This page describes hardware and software for controlling a stepper motor based lathe spindle manually, Such lathes are produced in China and can be commonly found on ebay.

Movement control is done using a potentiometer and button. With the potentiometer the speed and direction can be set, while the button allows to rotate at a specific angle, after which the motor stops.

After powering up, it is required to either rotate the potentiometer to the center position (speed: 0) or press the button to rotate exactly a configured amount of degrees. This is done to make sure that the spindle initially only rotates, when the user explicitly acknowledges. Afterwards the button can be pressed at any moment to rotate the same amount of degrees further. A BCD-switch is used to configure the angle. While the stepper motor is in pause state, to commence moving at a certain speed, it is necessary to first move the potentiometer to the center position from which the direction and speed can than be set accordingly.

Project summary:

The documentation of the stepper controller can be found here: hpsteppro_doku_2016_04.pdf

The wiring between the HP_Step.pro board and the Arduino nano controller is the following:

PIN FUNCTION DESCRIPTION ARDUINO PIN
CN4,1 RXD Unspecified 12
CN4,2 /Clock Clocksignal, rising edge causes step 9
CN4,3 /Error During low state 11
CN4,4 /CCW Rotation direction 4
CN4,5 /Off Power off stepper drivers 5
CN4,6 /Sleep Reduces motor current to 25% from nominal during low state 6
CN4,7 + CN4,8 +5v This pin was originally not connected (NC) and now repurposed to power the arduino controller from the internal 5v supply of the stepper controller +5v
CN4,9 + CN4,10 GND Ground GND
CN7.5 /Reset Reset 13

Arduino software using the FastAccelStepper library

//----------------------------------
// https://github.com/gin66/FastAccelStepper/blob/master/src/FastAccelStepper.h
// https://github.com/gin66/FastAccelStepper
// FastAccelStepper documentation:
// https://github.com/gin66/FastAccelStepper/blob/master/extras/doc/FastAccelStepper_API.md
//
// Arduino Hardware settings:
// Processor: ATmega328P (regular, not the Old bootloader)
// Board: Arduino Nano 3.0
// Port: /dev/ttyUSB0
//
// Dependency:
// Install the FastAccelStepper library by Jochen Kiemes (currently version 0.31.6)
 
 
#include "FastAccelStepper.h"
#include <stdint.h>
 
#define MAXSPEED 12000 // tested with stepper->setSpeedInHz(spd);
#define MINVAL 0 // smallest value from AD input
#define MAXVAL 1023 // largest value from AD input
#define LIMIT 2 // exclude zone for potentiometer at extreme angles
#define THRHLD 3 // hysteresis for potentiometer change
#define NUM_SAMPLES 10 // number of samples to use from potentiometer
 
 
// pin numbers definition:
// Number corresponds to name Dxx as on silkscreen and used in the function
// digitalWrite(pin_number). For example:
// 13 corresponds to D13, 9 corresponds to D9
const uint8_t rst_pin = 13; // rst pin for HP-Step.pro
const uint8_t rxd_pin = 12; // rx pin for some kind of tty communication
const uint8_t clk_pin =  9; // Step signal avr atmega328p: only Pin 9 and Pin 10.possible..
const uint8_t err_pin = 11; // error pin (active low)
const uint8_t ccw_pin =  4; // rotation direction
const uint8_t off_pin =  5; // switches output drivers off (active low)
const uint8_t slp_pin =  6; // reduces stepper current to 25% (active low)
 
 
const uint8_t led_pin =  7; // signal led to indicate angular mode connected between D7 and GND
 
// A0 corresponds with a #define to decimal 14, PIN_A0 is similar but a const uint instead.
// All input pins use the internal pull-up.
const uint8_t adj_pin = PIN_A0; // Analog pin A0 with 4k7 lin. potentiometer
const uint8_t rot_pin =  8; // connect a button (switch to ground) to rotate (90) degrees
 
// 2-digit bcd-wheel to set rotation angle. Common is connected to ground
const uint8_t bcd10 = PIN_A1;
const uint8_t bcd20 = PIN_A2;
const uint8_t bcd40 = PIN_A4;
const uint8_t bcd80 = PIN_A3;
const uint8_t bcd01 = PIN_A5;
const uint8_t bcd02 = 2;
const uint8_t bcd04 = 10;
const uint8_t bcd08 = 3;
 
// stepper definitions
const uint8_t stp360 = 200; // number of steps for stepper motor to rotate 360 degrees
 
// connected geometry (if stepper has a gear with another gear)
const uint8_t pg = 60; // number of teeth of primary gear
const uint8_t sg = 10; // number of teeth of secondary gear
const uint8_t steps_for_3deg = stp360 * 4 * (pg/sg) / 120; // smallest exact step is 3 degrees and corresponds with 40 clk pulses
 
// storage for potentiometer samples, rotation direction, blink time
static uint16_t pos[NUM_SAMPLES];
static uint8_t n;                  // samples array index
static uint32_t LedPrevMillis = 0; // will store last time LED was updated
enum patterns {LED_OFF, BLINK_SLOW, BLINK_FAST, LED_ON};
static enum patterns led_ptrn = BLINK_FAST;
 
// motor control
enum directions {BACKWARD = -1, STOP = 0, FORWARD = 1};
enum rotation_modes {CONTINUOUS, ANGULAR};
static enum directions stp_direction;
static enum rotation_modes rotation_mode;
 
// button debounce
const uint8_t min_debounce_ms = 20; // 20 ms debounce time
uint32_t btnPrevMillis;
 
FastAccelStepperEngine Engine = FastAccelStepperEngine();
FastAccelStepper *stepper = NULL;
 
void setup()
{
  pinMode(rst_pin,OUTPUT);
  digitalWrite(rst_pin,LOW);
  delay(1000);
  digitalWrite(rst_pin,HIGH);
 
  pinMode(led_pin,OUTPUT);
  digitalWrite(led_pin,LOW);
 
  delay(6000); // allow stepper controller to fully initialize
 
  pinMode(slp_pin,OUTPUT);
  digitalWrite(slp_pin,LOW); //Use full power for the stepper motor
  pinMode(off_pin,OUTPUT);
  digitalWrite(off_pin,LOW);
  pinMode(rot_pin,INPUT_PULLUP);
 
  // initialization for bcd wheel
  pinMode(bcd10,INPUT_PULLUP);
  pinMode(bcd20,INPUT_PULLUP);
  pinMode(bcd40,INPUT_PULLUP);
  pinMode(bcd80,INPUT_PULLUP);
  pinMode(bcd01,INPUT_PULLUP);
  pinMode(bcd02,INPUT_PULLUP);
  pinMode(bcd04,INPUT_PULLUP);
  pinMode(bcd08,INPUT_PULLUP);
 
  Engine.init();
  stepper = Engine.stepperConnectToPin(clk_pin);
  stepper->setDirectionPin(ccw_pin, false); // to invert direction, use argument "ccw_pin, false"
  stp_direction = FORWARD; // default movement for stepper
  stepper->setEnablePin(off_pin, false); // false means: active low
  stepper->setAutoEnable(true);
  stepper->setAcceleration(10000);     // Set the new acceleration value     
  stepper->stopMove();
  rotation_mode = ANGULAR; // require potentiometer to start from the center.
 
  /* fill array with initial values */
  init_array(analogRead(adj_pin));
 
  /* start value for debounce */
  btnPrevMillis = millis();
}
 
void move_degrees(uint32_t angle) {
  static int8_t step_counter = 0; // compensation counter. Based on consecutive triple calls give integer accuracy.
  stepper->stopMove();
  while (stepper->isRunning()); // wait for the motor to come to a full stop
 
  // formula: angle * 200 * 4 * (ratio) / 360 = 40 * angle / 3
  // where ratio = 60/10
  uint16_t steps    = steps_for_3deg * angle / 3;
  uint8_t remainder = steps_for_3deg * angle % 3;
 
  // Motor cannot step 13.3333 or 26.6666 steps. Therefore only integer values
  // are used and a compensation is added once every three calls.
  // 0 -> 13.333 -> 26.666 -> 40 will then become: 0 -> 13 -> 27 -> 40
  // for 1 degree angle rotations. All larger (integer) rotations are then just
  // a multiple of this schema.
  switch (remainder) {
    case 0:
      // leave result unchanged
      break;
    case 1:
      steps += (stp_direction == FORWARD) ? (step_counter == 1) : (step_counter == 2);
      break;
    case 2:
      steps += (stp_direction == BACKWARD) ? (step_counter != 1) : (step_counter != 2);
      break;
  }
 
  // precise movement based on natural numbers
  stepper->setSpeedInHz(MAXSPEED);
  stepper->move(stp_direction * (int32_t)steps); // cast for negative sign, move +/- 90 degrees
 
  while (stepper->isRunning()); // wait for the motor to come to a full stop
 
  // correction counter since we are not using floating point
  if (step_counter >= 2 && stp_direction == FORWARD) {
    step_counter = 0;
  } else if (step_counter <= 0 && stp_direction == BACKWARD) {
    step_counter = 2;
  } else {
    step_counter += (stp_direction == FORWARD);
  }
}
 
enum directions get_direction(uint16_t pos) {
  /**
   * Values between 525 and 1023 mean forward direction flag set
   */  
  if (pos > 525) {
    return FORWARD;
  } else if (pos < 499) {
    return BACKWARD;
  }
  return STOP;
}
 
uint16_t calc_speed(uint16_t pos) {
  /**
   * Values between 516 and 1023 mean forward direction flag set
   * Exclude STOP as value
   */
  if (get_direction(pos) != STOP) stp_direction = get_direction(pos);
 
  /**
   * Values between 562 and 1023 mean forward movement. Speed
   * is mapped from 0 to MAXSPEED with negative sign for forward movement
   */  
  if (pos > 562) {
    return map(pos, 563, 1023, 0, MAXSPEED);
  } else if (pos < 462) {
    return map(pos, 0, 461, MAXSPEED, 0);
  }
  return 0;
}
 
uint16_t capture_potentiometer(void) {
  pos[n++] = analogRead(adj_pin);
  if (n >= NUM_SAMPLES) n = 0;
  return calc_average();
}
 
uint8_t read_bcd_wheel(void) {
  return 10 * (!digitalRead(bcd10) | 
               !digitalRead(bcd20) << 1 |
               !digitalRead(bcd40) << 2 | 
               !digitalRead(bcd80) << 3) +
              (!digitalRead(bcd01) |
               !digitalRead(bcd02) << 1 |
               !digitalRead(bcd04) << 2 |
               !digitalRead(bcd08) << 3);
}
 
uint16_t calc_average(void) {
  uint16_t sum = 0;
  for (uint8_t i = 0; i < NUM_SAMPLES; i++) {
   sum += pos[i];
  }
  return sum/NUM_SAMPLES;
}
 
void handle_limits(uint16_t *avg, uint16_t *avg_prev) {
  if ( *avg >= MAXVAL - LIMIT && *avg_prev != MAXVAL ) {
    *avg = MAXVAL; //  force update
    *avg_prev = MINVAL;
  } else if ( *avg <= MINVAL + LIMIT && *avg_prev != MINVAL ) {
    *avg = MINVAL; //  force update
    *avg_prev = MAXVAL;
  }
}
 
bool is_spd_change_required(uint16_t *avg, uint16_t *avg_prev) {
  /* Use threshold to prevent too many successive speed changes */
  if (*avg == *avg_prev) return false;
  if (*avg > *avg_prev) {
    if (*avg - *avg_prev > THRHLD) return true;
    return false;
  }
 
  if (*avg_prev - *avg > THRHLD) return true;
  return false;
}
 
void set_speed(uint16_t spd) {
  if (!spd) {
    /* stop movement */
    stepper->stopMove();
    digitalWrite(slp_pin,LOW); // Use less power for the stepper motor
  } else {
    /* rotate with speed */
    digitalWrite(slp_pin,HIGH); // Use full power for the stepper motor
    stepper->setSpeedInHz(spd);
    set_direction();
  }
}
 
void init_array(uint16_t pv) {
  for (uint8_t i = 0; i < NUM_SAMPLES; i++) {
    pos[i] = pv;
  }
}
 
void set_direction(void) {
  if (stp_direction == FORWARD) {
    stepper->runForward();
  } else {
    stepper->runBackward();
  }
}
 
void prevent_movement(uint16_t *avg, uint16_t *avg_prev) {
  *avg = calc_average();
  *avg_prev = *avg;
}
 
void handle_angular_rotation(uint16_t *avg, uint16_t *avg_prev) {
  led_ptrn = LED_ON;
  handle_led_ptrn();
 
  *avg_prev = *avg;
  uint16_t pos = analogRead(adj_pin);
  if (get_direction(pos) != STOP) stp_direction = get_direction(pos);
  move_degrees(read_bcd_wheel()); // use direction from last movement
  rotation_mode = ANGULAR;
}
/**
 * After angular rotation it is required to operator
 * the potentiometer to go back to center to prevent
 * unexpected movement
 */
bool is_potentiometer_at_center(void) {
  return get_direction(analogRead(adj_pin)) == STOP;
}
 
void handle_led_ptrn(void)
{
  uint16_t blink_interval;
 
  switch (led_ptrn) {
    case LED_OFF:
      digitalWrite(led_pin, LOW);
      return;
    case LED_ON:
      digitalWrite(led_pin, HIGH);
      return;
    case BLINK_SLOW:
      blink_interval = 1000;
      break;
    case BLINK_FAST:
      blink_interval = 100;  
      break;
  }
 
  if (millis() - LedPrevMillis >= blink_interval) {
    LedPrevMillis = millis(); // save last time from LED blink
    digitalWrite(led_pin, !digitalRead(led_pin));
  }
}
 
//----------------------------------
//
//  Main loop
//
//
void loop() {
  static uint8_t n;
  static uint16_t avg = calc_average();
  static uint16_t avg_prev = avg;
 
  handle_led_ptrn(); // handle led blink patterns, based on static enum led_ptrn
  avg = capture_potentiometer(); // capture sample, add to array, return array average
  handle_limits(&avg, &avg_prev);
 
  if (rotation_mode == ANGULAR) {
    if (is_potentiometer_at_center()) rotation_mode = CONTINUOUS;
    else if (is_spd_change_required(&avg, &avg_prev)) led_ptrn = BLINK_FAST;
  }
 
  /* debounce + rotate certain degrees if button pressed */
  if (millis() - btnPrevMillis > min_debounce_ms) {
    if (!digitalRead(rot_pin)) {
      handle_angular_rotation(&avg, &avg_prev);
      while (!digitalRead(rot_pin)); // wait for button release
      btnPrevMillis = millis();
    }
  }
 
  /* handle continuous rotation */
  if (rotation_mode == CONTINUOUS) {
    led_ptrn = is_potentiometer_at_center() ? LED_ON : LED_OFF;
    if (is_spd_change_required(&avg, &avg_prev)) {
      avg_prev = avg;
      set_speed(calc_speed(avg_prev));
    }
  }
}