Linear actuator control with programmable positions

  Check out our new plug-and-play actuator position controller

 

We previously wrote a step-by-step tutorial on how to control a linear actuator with an Arduino and relays, and how to read a linear actuator encoder.  We applied this knowledge and created a control system that made linear actuator adjustable limits.

There are many applications that can make use of this position control ability; controlling valves, control generator or motor throttle, boat gear shift control, and countless more from the mundane to the elaborate. A general purpose system would be able to set programmable positions and return to them on command, as well as being able to manually control the linear actuator.

This example will use the dual relay board to control the actuator, and read the position encoder from the linear actuator with position feedback (CH-Series).

Circuit with Arduino, linear actuator, and relay board

Here's a diagram of how the linear actuator, relay board, and buttons connect to the Arduino.

Wiring diagram - linear actuator with programmable positionsAll the buttons are using internal pullup resistors on the microcontroller, so we just need to connect the button between the input pins and ground.  This simplifies the wiring considerably.  The relay board is connected to output pins 6 and 7, though you can set these to whichever pins work for you.  The linear actuator encoder is attached to the interrupt pins 2 and 3.

 Now the code

This code makes use of two libraries, a button library and an encoder library; both of which were used in previous articles.  You could code these functions yourself, debouncing switches and tracking revolution pulses and direction of encoders is not complicated, but if the code works well then why rewrite it.  Using the libraries also makes the code much more readable. Not only that, the encoder library has some high performance sections written in assembly.  It's been over 15 years since I've written anything in assembly, and I don't want to go there anymore!

#include <Button.h> //https://github.com/JChristensen/Button (link to dl)
#include <Encoder.h> //http://www.pjrc.com/teensy/arduino_libraries/Encoder.zip

 

We use constants for various pins, such as relays, buttons, and for automatic/manual mode for increased readability.

const int RELAY[] = {6,7};  //RELAY[0] and RELAY[1] to access the pins
const int BTN_EXTEND = 4;
const int BTN_RETRACT = 5;
const uint8_t MANUAL = 1;    //a constant to indicate manual mode
const uint8_t AUTOMATIC = 2; //a constant to indicate automatic mode
const int BTN_MEM_PIN[] = {8,9,10};
const int BTN_SET_MEM = 11;

Similar to how we set up the adjustable limits code, we set up the encoder and buttons.


//Set up the linear actuator encoder
//On many of the Arduino boards pins 2 and 3 are interrupt pins
// which provide the best performance of the encoder data.
Encoder myEnc(2, 3); 
long oldPosition  = -999;
long targetPosition = 0;
#define ACCURACY 10		   //How close to your target position is close enough. Higher accuracy may result in 
						   // a bit of jitter as the actuator nears the position
#define DEBOUNCE_MS 20     //A debounce time of 20 milliseconds usually works well for tactile button switches.
#define PULLUP true        //To keep things simple, we use the Arduino's internal pullup resistor.
#define INVERT true        //Since the pullup resistor will keep the pin high unless the
						   //switch is closed, this is negative logic, i.e. a high state
						   //means the button is NOT pressed. (Assuming a normally open switch.)
uint8_t MODE = MANUAL;

Button btnExtend(BTN_EXTEND, PULLUP, INVERT, DEBOUNCE_MS);
Button btnRetract(BTN_RETRACT, PULLUP, INVERT, DEBOUNCE_MS);
Button btnSetPos(BTN_SET_MEM, PULLUP, INVERT, DEBOUNCE_MS);
Button btnPos1(BTN_MEM_PIN[0], PULLUP, INVERT, DEBOUNCE_MS);
Button btnPos2(BTN_MEM_PIN[1], PULLUP, INVERT, DEBOUNCE_MS);
Button btnPos3(BTN_MEM_PIN[2], PULLUP, INVERT, DEBOUNCE_MS);

We have a constant (defined value) called ACCURACY.  This is our acceptable accuracy setting.  If we get within this many pulses of our target position, it's considered to be at the target position.  If you decrease this, you will experience jitter or hunting and pecking while the controller moves in on the target position.  What happens is the power to the motor is cut when the target position is achieved, but there is a very slight amount of drift.  This causes an overshoot of the target position, so the controller reverses the actuator, and this can repeat until the final target position is achieved. It's very rare that such a high accuracy is required, and if so you can use a PID algorithm (working on it) to decelerate the closer you get to the target position, thereby eliminating the hunting and pecking behavior. 

In this example we are going to hard code the initial position values at position 0.  In your project you could read and write to EEPROM in order to persist this data between power cycles.

long memPosition[] = {0,0,0};

In the setup() function we only need to specify OUTPUT for the relay pins. The button and encoder pins are set up from their libraries.

void setup() {
  pinMode(RELAY[0], OUTPUT);
  pinMode(RELAY[1], OUTPUT);

  Serial.begin(9600);  //for debugging
}

In our main program loop we are basically doing these tasks:

  • read the button states
  • manually move the actuator if we are using the manual buttons
  • move to memory positions if we have pressed a memory button
  • if we are in automatic mode (going to a memory position), we compare our current position with our target position and move accordingly.
  • if we are trying to save a position, save it.

Here's the full code listing:


#include  //http://www.pjrc.com/teensy/arduino_libraries/Encoder.zip
#include   //https://github.com/JChristensen/Button (link to dl)

const int RELAY[] = {6,7};  //RELAY[0] and RELAY[1] to access the pins
const int BTN_EXTEND = 4;
const int BTN_RETRACT = 5;
const uint8_t MANUAL = 1;    //a constant to indicate manual mode
const uint8_t AUTOMATIC = 2; //a constant to indicate automatic mode
const int BTN_MEM_PIN[] = {8,9,10};
const int BTN_SET_MEM = 11;

//Set up the linear actuator encoder
//On many of the Arduino boards pins 2 and 3 are interrupt pins
// which provide the best performance of the encoder data.
Encoder myEnc(2, 3); 
long oldPosition  = -999;
long targetPosition = 0;
#define ACCURACY 10		   //How close to your target position is close enough. Higher accuracy may result in 
						   // a bit of jitter as the actuator nears the position
#define DEBOUNCE_MS 20     //A debounce time of 20 milliseconds usually works well for tactile button switches.
#define PULLUP true        //To keep things simple, we use the Arduino's internal pullup resistor.
#define INVERT true        //Since the pullup resistor will keep the pin high unless the
						   //switch is closed, this is negative logic, i.e. a high state
						   //means the button is NOT pressed. (Assuming a normally open switch.)
uint8_t MODE = MANUAL;

Button btnExtend(BTN_EXTEND, PULLUP, INVERT, DEBOUNCE_MS);
Button btnRetract(BTN_RETRACT, PULLUP, INVERT, DEBOUNCE_MS);
Button btnSetPos(BTN_SET_MEM, PULLUP, INVERT, DEBOUNCE_MS);
Button btnPos1(BTN_MEM_PIN[0], PULLUP, INVERT, DEBOUNCE_MS);
Button btnPos2(BTN_MEM_PIN[1], PULLUP, INVERT, DEBOUNCE_MS);
Button btnPos3(BTN_MEM_PIN[2], PULLUP, INVERT, DEBOUNCE_MS);

long memPosition[] = {0,0,0};

void setup() {
  pinMode(RELAY[0], OUTPUT);
  pinMode(RELAY[1], OUTPUT);

  Serial.begin(9600);
}

void loop() {

  btnExtend.read();
  btnRetract.read();
  btnSetPos.read();
  btnPos1.read();
  btnPos2.read();
  btnPos3.read();

  if (btnExtend.isPressed()) {
    extendActuator();
    MODE = MANUAL;
  }

  if (btnRetract.isPressed()) {
    retractActuator();
    MODE = MANUAL;
  }

  if (!btnExtend.isPressed() && !btnRetract.isPressed() && MODE == MANUAL) {
    stopActuator();
    MODE = MANUAL;
  }

  if(btnPos1.wasReleased()) {
    Serial.println("btnPos1");
    MODE = AUTOMATIC;
    targetPosition = memPosition[0]; 
  }
  if(btnPos2.wasReleased()) {
    Serial.println("btnPos2");
    MODE = AUTOMATIC;
    targetPosition = memPosition[1]; 
  }
  if(btnPos3.wasReleased()) {
    Serial.println("btnPos3");
    MODE = AUTOMATIC;
    targetPosition = memPosition[2]; 
  }


  //check the encoder to see if the position has changed
  long newPosition = myEnc.read();
  if (newPosition != oldPosition) {
    oldPosition = newPosition;
    Serial.println(newPosition);
  }

  if(MODE == AUTOMATIC && newPosition != targetPosition) {
    Serial.print("Target/Actual:");Serial.print(targetPosition);Serial.print(" / ");Serial.print(newPosition);Serial.print(" [");Serial.print(abs(targetPosition - newPosition));Serial.println("]");
    if(targetPosition < newPosition) {
      Serial.println("AUTO RETRACT");
      retractActuator();
      MODE = AUTOMATIC;
    }
    if(targetPosition > newPosition) {
      Serial.println("AUTO EXTEND");
      extendActuator();
      MODE = AUTOMATIC;
    }
    if( (targetPosition == newPosition) || abs(targetPosition - newPosition) <= ACCURACY) {
      Serial.println("AUTO STOP");
      stopActuator();
      MODE = MANUAL;
    }
  }
  
  if(btnSetPos.isPressed()) {
   if(btnPos1.isPressed())
     memPosition[0] = newPosition;
   if(btnPos2.isPressed())
     memPosition[1] = newPosition;
   if(btnPos3.isPressed())
     memPosition[2] = newPosition;
       
  }
}

void extendActuator() {
  //Serial.println("extendActuator");
  digitalWrite(RELAY[0], HIGH);
  digitalWrite(RELAY[1], LOW);
}

void retractActuator() {
  //Serial.println("retractActuator");
  digitalWrite(RELAY[0], LOW);
  digitalWrite(RELAY[1], HIGH);
}

void stopActuator() {
  //Serial.println("stopActuator");
  digitalWrite(RELAY[0], HIGH);
  digitalWrite(RELAY[1], HIGH);
}

 

Troubleshooting

If your actuator keeps moving in one direction when you press a memory button, it's most likely that you need to reverse the two encoder wires going to Arduino pins 2 and 3.  Meaning move the encoder wire that was connected to pin 2 to pin 3, and the encoder wire that was connected to pin 3 to pin 2.

If your actuator retracts when you want it to extend, or extends when you want it to retract you can swap the motor wires at the relay board.

Any other issues with running the code?  Let us know.

Here's a video showing the linear actuator control in action: