Actuator with optical encoder

Any hardware type questions or problems for all other Phidget devices.
Post Reply
DaeviaAlex
Phidgetsian
Posts: 5
Joined: Thu Dec 15, 2022 12:06 am
Contact:

Actuator with optical encoder

Post by DaeviaAlex »

Hello,

I was wondering if somebody could help me setup an Optical Feedback Actuator with my Phidgets.

I purchased a Firgelli Optical Feedback Actuator for a test rig (#FA-OS-400-12-9 to be precise), and I am trying to connect it to a DC1000 motor controller.
I have been able to easily connect and control the motor side of the actuator to the DC1000. I can move it up and down with the Phidget Control Panel, everything works well.

Now, I would like to read its position with the integrated optical encoder. This encoder has 3 wires - blue (5V), yellow (GND), green (Output). Based on what's available on Firgelli's website, it is required to add a 10-15kOhm resistor between the encoder Output and the reading device (the DC1000 here). I added a 15kOhm resistor.

I tried connecting the 3 wires to the Encoder input of DC1000. 5V into 5V - Gnd into G - Output into B, A, or I. I tried changing the IO Mode like it is suggested in the DC1000 User Guide. It is not working. It would make sense since I think that the main issue here is that this integrated Optical Encoder is probably not a Quadrature Encoder.

I then tried to connect it to the Analog In input of the DC1000 thinking that I could read the Voltage Ratio instead. I do get a reading (~0.050V/v), but the value does not really change, no matter what position the actuator is in. It slightly fluctuates when the actuator moves (+/-0.005) but then it goes back to a somewhat similar value once it stops.
See graph attached: the first part shows the readings for a full extension until it stops, then a full retraction until it stops, then another extension that stops halfway. As you can see, the readings are not stable enough, especially when the actuator is moving.
Graph.PNG
Graph.PNG (41.99 KiB) Viewed 9495 times


Is there anything that I missed or that I am not doing properly?
Am I missing a piece of hardware? If so, which one?

Or is this type of encoder just not compatible with Phidgets?

I need to be able to record the actuator's position while it moves.

Any help will be greatly appreciated.
Thank you!
Alex
User avatar
mparadis
Site Admin
Posts: 959
Joined: Fri Oct 28, 2011 12:17 pm
Contact:

Re: Actuator with optical encoder

Post by mparadis »

Based on the description on Firgelli's website and the graph you posted, it looks like the encoder just provides a single channel of pulses, with 10 pulses = one rotation.

If this is the case, you'd need to write a program that can count those pulses. But I think it'd be hard to get reliable data if the waveform looks like that. Does it look any better if you don't use the resistor?
DaeviaAlex
Phidgetsian
Posts: 5
Joined: Thu Dec 15, 2022 12:06 am
Contact:

Re: Actuator with optical encoder

Post by DaeviaAlex »

Thanks for your reply mparadis.

Here's another voltage ratio graph with the same extension/retraction/half-extension motion, but without the resistor on the output.
Graph2.PNG
Graph2.PNG (44.98 KiB) Viewed 9458 times
Here are also pictures of the optical encoder at the back of the actuator:
IMG_20221220_003038.jpg
(2.56 MiB) Not downloaded yet
IMG_20221220_002822.jpg
(2.67 MiB) Not downloaded yet
If I understand correctly: I would not be able to use the encoder input on the DCC1000 since it is designed for a quadrature encoder, and the Voltage ratio input would also be useless for my application considering the unstable data that I am getting on the graphs.
When you say that I would have to write a program to count the pulses, does that mean that I would need to connect the encoder directly to the VINT hub and then open a Voltage Input Port channel to read the raw pulses and convert that to a linear distance using "100 pulses = 1in" (as per Firgelli's website)? Or is it more complicated than that?

I was also wondering if connecting the encoder output to both the B and A channels on the encoder input could give me some sort of usable data with the DCC1000. I know that I would not be able to get a sense of what direction the actuator is going in since both channels would get the same info, but for my application, it would not be an issue.
Maybe a bit of background on the application itself would not hurt: It is basically a 3-point flexural test rig where the actuator extends and pushes on a tube to flex it. A load cell is connected to the actuator to record the load vs displacement while the tube bends. Which is why I need to be able to read the actuator's displacement.
In the end, all I want to do is tell the actuator to extend to a certain position at a certain speed and record the load with the load cell while it does so.

I am also thinking about maybe replacing the encoder on the actuator with the HKT22 encoder but the motor shaft has a 8mm diameter...
User avatar
mparadis
Site Admin
Posts: 959
Joined: Fri Oct 28, 2011 12:17 pm
Contact:

Re: Actuator with optical encoder

Post by mparadis »

DaeviaAlex wrote: Tue Dec 20, 2022 11:22 am When you say that I would have to write a program to count the pulses, does that mean that I would need to connect the encoder directly to the VINT hub and then open a Voltage Input Port channel to read the raw pulses and convert that to a linear distance using "100 pulses = 1in" (as per Firgelli's website)? Or is it more complicated than that?
The tricky part will be detecting the pulses. Your voltageInput channel will just be streaming back events with voltage=52mV, voltage=50mV, voltage=48mV, etc.

Your program will have to use timing and thresholds to decide what constitutes a pulse and what doesn't. For example, in your graph it looks like the first movement has 11 pulses in it. But depending on how you calculate a pulse, it might interpret that first pulse as two pulses because of the little jagged peak on it. If there's already some kind of arduino library or other code sample that is intended to be used with this encoder, you may be able to port the code into your own Phidget program.
DaeviaAlex wrote: Tue Dec 20, 2022 11:22 am I was also wondering if connecting the encoder output to both the B and A channels on the encoder input could give me some sort of usable data with the DCC1000. I know that I would not be able to get a sense of what direction the actuator is going in since both channels would get the same info, but for my application, it would not be an issue.
I don't think this will work because the encoder interface is expecting to see two waveforms that are offset by a specific delay (a normal quadrature encoder has two sensors slightly offset so the leading or lagging of the two signals allows you to know the direction of rotation).
DaeviaAlex
Phidgetsian
Posts: 5
Joined: Thu Dec 15, 2022 12:06 am
Contact:

Re: Actuator with optical encoder

Post by DaeviaAlex »

So I connected the encoder directly to the VINT hub with the resistor and monitored the voltage input with a 1ms data interval.

Here is what I got during an extension:
Graph extend.PNG
(162.63 KiB) Not downloaded yet

And here is what I got during a retraction:
Graph3.PNG
(151.77 KiB) Not downloaded yet

As you can see, the graph is much clearer now.
The actuator is moving at full speed, which is ~15sec for a full retraction and the same for a full extension.

The first thing that is noticeable here: I have pulses. I counted around 60 pulses for 1sec during the retraction phase for example.
Which comes down to 900pulses in 15sec for a 9in displacement, and works with what Firgelli claims on their website (100pulses/in, 10 motor rotations).

Now the "issue" is that these pulses also come in a sort of sine wave, and I am having trouble coming up with a proper way to identify a pulse in a program. As you can see, the minimum of some pulses is pretty much equal to the maximum of other pulses. I was thinking about filtering the data by substracting a rough sine wave to to the main signal.

The other issue that I have is that sometimes the encoder sends a fairly stable voltage when the actuator is not moving, and sometimes not. See graph below. At position 0in, I almost get a line, then we have the extension phase, and then at position 9in the data is all over the place before the actuator is retracted back to 0in.
Extension - retraction.PNG
(192.69 KiB) Not downloaded yet

As recommended, I did find some Arduino tutorials on Firgelli's website with some code examples ("How to Read Feedback from an Optical Sensor" and "Feedback from a Hall Effect Sensor With Video"). I am not really sure how to port this code to Python though... It seems like they are only reading pulses with the RISING parameter of the attachInterrupt() function. Is their a similar function with Python (apologies if this is a simple question, I am only starting with Python)?

Code: Select all

long steps = 0;   // Pulses from  Optical Sensors
void setup() {
  pinMode(2, INPUT);
  attachInterrupt(digitalPinToInterrupt(2), countSteps, RISING);
}

void loop () {}

void countSteps(void) {
  steps++;
}
Am I wasting my time trying to figure out a way to make this encoder work with Phidgets?
The encoder disc is currently screwed onto the 8mm shaft with a 4mm screw and it looks like it could be possible to connect your HKT22 encoder disc on this screw. I could then 3D print a bracket to connect the body to the actuator frame. Would that make sense?
I decided to go with Phidgets this time for this project, mainly because I needed a quick solution to run my tests so I can move quickly onto the next phase.
DaeviaAlex
Phidgetsian
Posts: 5
Joined: Thu Dec 15, 2022 12:06 am
Contact:

Re: Actuator with optical encoder

Post by DaeviaAlex »

So I was able to write a program using the Digital Input of the VINT hub to record the encoder rotation.
I plugged the encoder directly to the VINT and used the getState() method to record the pulses. Very similar to what you could do with an Arduino.

Note that the DCC1000 Target Velocity has to be set to a max of 0.5. At greater speeds, the VINT hub is not able to properly and nicely detect the pulses. I was getting an eratic and sometimes almost flat line on my graph in the Phidget Controller panel at full speed for example. I guess the encoder disc spins too fast for the encoder to provide a strong and steady signal, or it sends pulses too fast for the VINT hub to record them.

It is in no way perfect, there are probably better ways to write this, but for what it's worth, here is my version.
Hope that this could help someone in the future!

All you have to do is set what you want in the "REQUESTED PARAMETERS" section.
The program then moves the actuator to the requested position and record+correct the final position in case there is an error caused by its deceleration.

Code: Select all

from Phidget22.Phidget import *
from Phidget22.Devices.DigitalInput import *
from Phidget22.Devices.DCMotor import *
import time

def main():
    #Create your Phidget channels
    DigitalInput0 = DigitalInput()
    DigitalInput0.setIsHubPortDevice(True)
    DigitalInput0.setHubPort(0)
    DigitalInput0.openWaitForAttachment(1000)

    dcMotor = DCMotor()
    dcMotor.setHubPort(1)
    dcMotor.openWaitForAttachment(1000)
    dcMotor.setCurrentLimit(4) #Actuator current limit
    
    #------- Do stuff with your Phidgets here or in your event handlers. ------#
    
    #-- VARIABLES --#
    pulse = float(0) #initial pulse = 0
    extrapulse = float(0) #initial extra pulse for deceleration = 0
    test = 0 #variable to test if pulse was already recorded
    timeout = 5 #Time used to record extra pulses when decelerating.
    timeout2 = 2 #Time out time to break the loop
    
    #-- REQUESTED PARAMETERS --#
    move = 1 #actuator position requested in inches
    pulsemove = move*100 #convert inches to pulse (1in = 100 pulses)
    velocity = 0.3 #Actuator speed (MAX 0.5)
    
    
    #-- ACTUATOR MOVES UNTIL REQUESTED POSITION IS ACHIEVED --#
    
    #1. Extend actuator
    dcMotor.setTargetVelocity(velocity)
    
    #2. Read and print initial parameters
    state = DigitalInput0.getState()
    print("Initial pulse: " + str(pulse))
    print("Initial state: " + str(state))
    
    #3. Check and add pulses
    #WHILE current pulse is smaller than requested pulse (position)
    while pulse < pulsemove:
        #Read digital input signal
        state = DigitalInput0.getState()

        #IF digital input is HIGH and pulse has not been recorded yet, THEN add pulse and change test variable.
        if (state == True) and (test == 0):
            pulse = pulse + 1
            test = 1
            print("Pulse: " + str(pulse))
        #OTHERWISE, WHILE digital input is still HIGH (same hole on the encoder disc): wait and read digital input. ONCE digital input is not HIGH, change test variable.
        else:
            while state == True:
                state = DigitalInput0.getState()
            #Reset test variable
            test = 0

    #4. Stop actuator command
    dcMotor.setTargetVelocity(0)
    
    #NOW pulse == pulsemove
    #5. Reset test variable
    test = 0


    #-- RECORD EXTRA PULSES WHILE ACTUATOR IS DECELERATING --#
    
    #1. Record current time
    timeout_start = time.time()
    
    #2. Record extra pulses
    #WHILE current time is smaller than start time + timeout
    while time.time() < (timeout_start + timeout):
        #Read digital input signal
        state = DigitalInput0.getState()
        
        #IF digital input is HIGH and pulse has not been recorded yet, THEN add extrapulse, add pulse, and change test variable.
        if (state == True) and (test == 0):
            extrapulse = extrapulse + 1
            pulse = pulse + 1
            test = 1
            
        #OTHERWISE, WHILE digital input is still HIGH (same hole on the encoder disc): wait and read digital input. ONCE digital input is not HIGH, change test variable.
        else:
            #Record current time to have a way to break the WHILE loop if encoder is stopped and reports a HIGH digital input indefinitely
            timeout_start2 = time.time()
            while state == True: 
                if time.time() < (timeout_start2 + timeout2):
                    state = DigitalInput0.getState()
                else:
                    break
            test = 0
            break
    
    #3. Print extra pulses recorded
    print("Total pulses: " + str(pulse))
    print("Extra pulses: " + str(extrapulse))
    
    
    #-- CORRECT ACTUATOR POSITION --#
    
    #1. Retract actuator
    dcMotor.setTargetVelocity(-velocity)
    
    #2. Check and correct extra pulses
    #WHILE extra pulses still have not been corrected
    while extrapulse > 0:
        #Read digital input signal
        state = DigitalInput0.getState()
        
        #IF digital input is HIGH and pulse has not been recorded yet, THEN add pulse and change test variable.
        if (state == True) and (test == 0):
            extrapulse = extrapulse - 1
            pulse = pulse - 1
            test = 1
        #OTHERWISE, WHILE digital input is still HIGH (same hole on the encoder disc): wait and read digital input. ONCE digital input is not HIGH, change test variable.
        else:
            while state == True:
                state = DigitalInput0.getState()
            #Reset test variable
            test = 0
    
    #3. Print final pulse
    print("Final pulse: " + str(pulse))
    
    #4. Stop actuator
    dcMotor.setTargetVelocity(0)



    #Close channels
    DigitalInput0.close()
    dcMotor.close()

main()


Any comments or tips to make it better will be greatly appreciated!
Post Reply

Who is online

Users browsing this forum: No registered users and 2 guests