This semester I'm enrolled in an embedded systems class. I realized during the first few weeks that the class was probably a waste of an elective (it's more of an intro class, though it shouldn't be, and I'm not getting much out of it) so I've had to get a little more creative in the class labs in order to keep myself occupied.

This lab required writing a "driver" library for a new piece of hardware. I had just found two old HP inkjet printers in my parents' basement, and I figured it'd be fun to reverse engineer the linear encoder and play with a practical controls problem. Old printers are a treasure trove of awesome parts to hack with. Lots of rods, bearings, springs, motors, gears and electronics. Here's the teardown process.

reverse engineering the carriage assembly

The first thing I did was build a little wooden stand for the carriage assembly to sit on. I used a wood panel from the stereo I harvested the VU meters from, and then some extra scraps lying around my apartment. I drilled holes to mount a barrel jack into so the assembly could be powered from a wall-wart DC power supply, and drilled holes to pass zipties through to mount a breadboard.

optical encoder

Most of these inkjet printer carriages use DC motors with feedback control from some sort of position sensing mechanism. This printer uses this optical encoding strip, which has transparent and opaque stripes along the length.

image

This strip passes through an optical encoder, causing the light inside the encoder to be periodically interrupted. There are usually two photodetectors inside the encoder -- a single emitter/detector pair would allow for sending of speed, but not direction, as moving the carriage in either direction would produce an identical output on the interrupter (a square wave). If two photodetectors are used, then one emitter/detector pair is "interrupted" in sequence, one before the other. The output is two square waves, one which lags or leads in phase by 90 degrees from the other, depending on the direction that the strip is traveling through the encoder. Here's an image which describes the effect.

image

I didn't have much luck finding a datasheet by searching the various numbers that were on the exterior of the package, so I'm assuming it was a part that was custom manufactured for HP printers. Instead, I soldered wires onto every pin of the encoder itself to inspect its operation. I kept all of the electronic guts of the printer, which I managed to figure out how to reconnect. This let me turn the printer on and manually move the carriage to inspect the output of the encoder. I got lucky that the printer turns the encoder on constantly, and not just during printing.

image

Here's a video I took showing the state of the different encoder pins while it is in motion.

From this, I was able to determine which pins were the output of the encoder, and which pins powered the encoder. The easiest to figure out were the ground pin and the two signal pins. A little more confusing were two pins that were sitting at about 3.3V and one pin that was sitting at about 1.9V. So, I took a guess that there were two infrared LEDs inside the encoder arranged in a common cathode configuration. Infrared LEDs have a low forward voltage (forward voltage and wavelength are inversely related) compared to visible LEDs (a red led has a typical forward voltage of about 2V), which explains the approximate 1.4V drop between the pins.

To power it myself, I needed to know the rated forward current of the LEDs inside the package. I could have cut a trace on the PCB and sensed the cathode current using the voltage across a small valued resistor. Instead, I started with a high valued current limiting resistor, connected the anodes to 3.3V, measured the voltage on the cathode and adjusted the resistor value until I saw about 1.9V on the cathode.

motor control

This was relatively straightforward. I happened to have a Toshiba TB6612FNG breakout board from Pololu handy, which is what I used. The IC is a dual H-Bridge driver. It accepts a PWM signal, so by changing the duty cycle you change the average voltage that is delivered to the motor. The input pins control the polarity that the motor is driven with. Before I wrote any more code, I couldn't resist the urge to hook up some buttons to just turn the motor on in either direction. Here's the result of that.

interfacing

The LPC1768 on the mbed has edge triggered interrupts which I used to detect a rising or falling edge on each output of the encoder. It also has a single quadrature encoder peripheral, but its dedicated pins are not exposed on the mbed, and I am planning on driving two of these carriages for a later project, so I needed to create a solution in software. I used the mbed "standard library" which has classes which perform most of the peripheral configuration. I makes me feel a little too abstracted for an embedded environment, but it's nice to not have to worry about a lot of the hardware details for once.

I created a relatively simple C++ class that represents a "print head" which keeps track of the current position on the encoding strip in "ticks" (initializes to zero), and a current "goal" position which it tries to hold. In what could potentially be called bad design, the class implements a PID control loop internally. The carriage can be moved by changing the goal value.

#include "mbed.h"

class PrintHead {
public:

    // positive is to the right
    // negative is to the left
    int count;
    int goal;
    int last_error;
    float error_integral, output, iterm, dterm;
    float dt;
    float ki, kp, kd;

    PrintHead(PinName left_motor_pin, 
              PinName right_motor_pin, 
              PinName motor_pwm_pin,
              PinName left_encoder_pin,
              PinName right_encoder_pin) :
              _left_motor(left_motor_pin),
              _right_motor(right_motor_pin),
              _motor_speed(motor_pwm_pin),
              _left_encoder(left_encoder_pin),
              _right_encoder(right_encoder_pin) {
        
        // change the motor pwm speed for smooth motor operation
        // if the pwm frequency is too low the motor jerks the
        // print head along the track as the PWM switches on and off
        _motor_speed.period(0.00001);
        _motor_speed = 0;
        
        _left_encoder.rise(this, &PrintHead::left_encoder_rising);
        _left_encoder.fall(this, &PrintHead::left_encoder_falling);
        _right_encoder.rise(this, &PrintHead::right_encoder_rising);
        _right_encoder.fall(this, &PrintHead::right_encoder_falling);
        
        dt = 0.001;
        _update_motor_ticker.attach_us(this, &PrintHead::update_motor, 1000);
        
        count = 0;
        goal = 0;
        error_integral = 0;
        kp = kd = ki = 0;
    }
        
    void left_encoder_rising() {
        if(_right_encoder) count--;
        else count++;
    }
    
    void left_encoder_falling() {
        if(_right_encoder) count++;
        else count--;
    }
    
    void right_encoder_rising() {
        if(_left_encoder) count++;
        else count--;
    }
    
    void right_encoder_falling() {
        if(_left_encoder) count--;
        else count++;
    }
    
    void update_motor() {
        _left_motor = 0;
        _right_motor = 0;

        int error = goal - count;

        error_integral += error * dt;
        iterm = ki * error_integral;
        dterm = kd * ((error - last_error) / dt);
        
        output = ((kp * error) + iterm + dterm);
        
        if(abs(output) > 1) _motor_speed = 1;
        else _motor_speed = abs(output);
        
        _left_motor = (output < 0);
        _right_motor = (output > 0);
        
        last_error = error;
    }
    
private:
    DigitalOut _left_motor;
    DigitalOut _right_motor;
    PwmOut _motor_speed;
    InterruptIn _left_encoder;
    InterruptIn _right_encoder;
    Ticker _update_motor_ticker;  
};

I change the PWM frequency of the PWM output in the constructor. I found that the default PWM period is large enough to jerk the carriage as it's moving. The next few lines sets up methods to execute on the rising and falling edge of each encoder output. A "ticker" (really just a timer) is then setup to call the PID control loop method periodically (every 1ms).

The four interrupt methods increment or decrement the current location of the carriage depending on the state of the other encoder output. This logic can be derived by consulting the diagram that was shown earlier.

The update_motor method implements the most basic of PID control loops. I'm controlling on position, which means I have no native control on velocity, acceleration, or jerk. However, those can be metered by implementing higher level control -- controlling how often the position goal is adjusted. The last lines of the method set the motor direction. There is no "left" or "right" motor, just two pins that control if the motor moves the carriage left or right.

buttons

For a grade on the project, I just used two buttons were to move the carriage to the left or right by a set number of ticks.

#include "mbed.h"
#include "DebounceIn.h"
#include "PrintHead.h"

DebounceIn left_pb(p20);
DebounceIn right_pb(p19);

PrintHead head(p21, p22, p23, p24, p25);
Serial pc(USBTX, USBRX);

bool previous_left_pb;
bool previous_right_pb;

int main() {
    left_pb.mode(PullUp);
    right_pb.mode(PullUp);
    pc.baud(57600);

    head.kp = 0.08;
    head.ki = 0.0005;
    head.kd = 0;

    while(1) {
        pc.printf("$%d %d;", head.goal, head.count);
        if(!left_pb && (left_pb != previous_left_pb)) head.goal -= 2000;
        else if(!right_pb && (right_pb != previous_right_pb)) head.goal += 2000;
        wait_us(1);
    }
}

Tuining the PID took a little of work. There was some resonance problems initially.

After a little tuning, it was working reliably. The buttons move the carriage by a set number of "ticks" and after disturbing the position of the carriage it returns to it's commanded position.

having some fun

While buttons were neat, I thought it would be a little more interesting to take an analog input and interpret it as the goal position of the carriage. This way an external signal could be used to drive the carriage to a position. I also output the current position of the carriage as a voltage using the DAC on the mbed. With this input-output system, I could drive the position of the carriage using my function generator, and observe the difference between the instantaneous commanded position and actual position. By driving the system with a sine wave and playing with the input frequency, frequency response of the system can be observed. As the input frequency increases the magnitude of the carriage displacement decreases, as the motor isn't physically capable of moving the carriage back and forth quickly enough to match the input.

The step response could also be observed by setting the input waveform to a square wave. There's little overshoot, which is optimal for my later purpose. Once the square wave frequency increases to a certain point, the position waveform starts to look sinusoidal, meaning the system is effectively a low-pass filter, which is somewhat expected and consistent with the previous results with increasing sine input frequencies.

In addition to being interesting, it was also just pretty fun. The video doesn't show much of the carriage moving, as it's hard to show both my scope display and the assembly, but you can hear the sounds it makes change with the scope display