ECE 4760: Laboratory 3
One DOF helicopter
Introduction.
You will build a one degree-of-freedom hovering device which allows the user to select the hover angle then controls the lift-motor with user-selectable parameters to maintain constant angle as the load changes. The motor output signal and actual angle will be displayed as waveforms on the oscilloscope. You will use ProtoThreads and write your program as tasks, but the control loop will need to run in an ISR. A video of a prototype is running here, and with waveform output, and stepping angles with tuned PID.
Procedures.
2017 video
A 2017 solution video of the system built by Kristen Marie Vilcans and Ramita Pinsuwannakub.
Lectures from 2017 describing the control system.
Lecture 18 PID.
Lecture 19 PID approximations.
Lecture 20 ADC and debugging details.
2019 solution videos
--Lab 3 Video built by Rebecca Bell, Emma Kaufma, Chloe Kuo
--Carlos Gutierrez, Alberto Lopez Delgado, Wilson Llivichuzhca
Manually-tested PID control: https://youtu.be/y3sCwsAsqug
Sequence test: https://youtu.be/IZWABqrFUwg
Connections:
- As in lab 1, the SPI DAC you will use is the MCP4822.
Use the examples shown on the Dev board page.
Perhaps Serial_1_2_3_test_all.c
- Possible pin assignments for PWM, ADC, serial and control buttons.
- An ADC channel for angle sensor.
Keep the ADC input line as far as possible from the SPI control signals.
Perhaps use A5 or A1.
- PWM via output compare unit, perhaps OC1 on RPB7
- Serial default for protothreads (1.3.2) uses pins:
PPSInput (2, U2RX, RPA1);
PPSOutput(4, RPB10, U2TX);
Be sure to uncomment #define use_uart_serial in the config file.
- A button connected to Vdd through 300 ohm resistors,
going to RA2 or RA3 with pulldown resistor turned on.
Or use the port expander RY0
with pullup turned on.
Concurrency:
For this assignment you must write your code using ProtoThreads 1_3_2 or later.
I suggest the following thread layout, but you can use anything that works for you:
- Thread 1 takes user input from the consol keyboard to set up PID parameters and the desired angle.
(example serial thread)
- Thread 2 Updates the LCD at around 10 times per second, only if you need status info.
- A timer ISR running at 1 KHz:
-- Reads the ADC to get the actual beam angle.
-- Runs the PID control loop at 1000/sec using the angle measurements
from the potentiometer
-- Sets a hardware PWM signal using output-compare unit to control the motor. (see below for setup)
using the command: SetDCOC3PWM(pwm_on_time);
-- Writes to channel A of the SPI DAC with the actual beam angle to be displayed as waveform on the oscilloscope.
-- Writes to channel B of the SPI DAC
with the motor control signal to be displayed as waveform on the oscilloscope.
- An output compare unit uses a timer to produce the actual motor control PWM signal in hardware.
- In Main you will set up the output compare unit.
Setup output compare:
// === Config timer and output compare to make PWM ========
// set up timer2 to generate the wave period -- SET this to 1 mSec!
OpenTimer2(T2_ON | T2_SOURCE_INT | T2_PS_1_1, generate_period);
// Need ISR to compute PID controller
ConfigIntTimer2(T2_INT_ON | T2_INT_PRIOR_2);
mT2ClearIntFlag(); // and clear the interrupt flag
// set up compare3 for PWM mode
OpenOC3(OC_ON | OC_TIMER2_SRC | OC_PWM_FAULT_PIN_DISABLE , pwm_on_time, pwm_on_time); //
// OC3 is PPS group 4, map to RPB9 (pin 18)
PPSOutput(4, RPB9, OC3);
Then, when you want to set the PWM dutycycle value, perhaps in the control loop ISR,
SetDCOC3PWM(unsigned int dutycycle);
where dutycycle is the duration, in timer counts, of the PWM-high
(for a 1 MSec period, PWM dutycycle is 0-39999)
Serial Interface connection to PC
See the Serial page for detailed directions on connection to the PC.
Also, the software section of the Development board page includes a program Serial_1_2_3_test_all.c,
which gives an example of the Protothreads 1_3_2 serial useage.
Angle sensor:
The angle sensor is a 10K potentiometer which costs over $20! Therefore you will ALWAYS limit current through the potentiometer by connecting a resistor in series with the wiper (pin 2), as shown below! The MCP6242 opamp acts as a unity-gain buffer for the anti-aliasing low-pass filter. You will pick C to be the appropriate low-pass filter for the 1 KHz sample rate. You will connect the output of the opamp to one of the ADC channels on the PIC32.
Motor Control:
You will need to control the lift-motor from the mcu. DC motors can cause
nasty inductive spikes to wipe out the transistors in the mcu port. The
circuit shown below is fairly safe. An optoisolator completely isolates
the MCU from the motor. The diode placed across the motor shorts out spikes
when the motor is turned off on every PWM pulse. The resistor grounding the base of the phototransistor
should be set for best falltime, probably around 1Mohm. The motor capacitor
should start around 0.1uf. Increase it if there is too much spike noise on
the analog input, but be sure to use ceramic capacitors, not electrolytic.
Electrolytic capacitors are too slow. The pinout of the 4N35 optoisolator
and power MOSFET are shown. Use either 2SK4017 or IRF640, or AOT2618. The AOT part has the lowest turn-on threshold. Note that the bandwidth
of the 4N35 is low, so use a low PWM frequency, perhaps about 1000
Hz.
Pin 1 on the 4N35 is marked with a "Y".
Building/simulating the 1-DOF sensor/beam/motor
You will construct the hovering device, similar to the images below.
Remember that your group gets ONE sensor potentiometer to use, so be careful.
Estimate the natural period and damping coefficient of the beam/motor/sensor that you built. You need these values for the system modeling and tuning. The natural period is approximately the simple pendulum natural period. T=2⋅π⋅√(L/g). Where L is the distance from the pivot to the motor, and g is gravitational acceleration. Using the DAC output to the scope, you can estimate the natural period. Also count the number of full cycles that the actual beam makes before it stops, and adjust the damping coefficient in the matlab code (DD) until the undriven pendulum matches the number of cycles. There are two versions of the matlab code. The first is a simulator using radian measure (with some guesses about motor thrust scaling). The second simulator uses angles measured in ADC units and motor control in PWM units, as shown below. The red line is the target angle.
The ADC will probably be set up to measure the 10Kohm servo potentionmeter from zero volts to Vref, resulting in ADC units of 0 to 1023 representing the resistance range of 0 to 10kohm. According to the potientiometer datasheet, the 10K resistance range occurs over 340 degrees of rotation. The useful range of angles for this lab will be 180 degrees (hanging down to vertical above pivot point). The resistance range you can use is therefore 180/340*10Kohm=5.29Kohm, so the raw ADC range will be about 5.29/10*1024=542 counts for 180 degrees rotation. If we set up the potentiometer to read about 520 ADC counts when the beam is hovering at horizontal position, then when hanging straight down the resistance will be about 520-271=249, and when directly over the pivot point about 790.
Building the 1-DOF device:
- Hot glue a motor to one end of the wooden beam.
NOTE: Orient the motor shaft to be at right-angles to the rotation shaft of the knob.
(motor: Coolplay Propellers Rotor Set & 4pcs Motor Set for Cheerson CX-10 CX-10A RC Quadcopter)
- Roughen the knob surface using sandpaper. Be sure to remove the plastic film.
- Hot glue the other end of the wooden beam to the knob surface.
- Solder a pair of wires (from ribbon cable) to the motor and tape them to the beam.
NOTE: Use only stranded wire peeled off from ribbon cable
The wires themselves can add weight and torque to the beam. Route them close to the
potentiometer shaft to minimize torque.
- Screw the potentiometer bracket to a chunk of wood big enough that you can use a book to weight it down.
Use #4 wood screws, as shown in this image.
Hot gluing the bracket to the wood will cost you 10 points on the lab.
- The potentiometer mounting hole on the bracket is slightly too small for the potentiomenter sleeve. You will need to
use the rat-tail (round) file to enlarge the hole.
- When attaching the potentiometer to the mounting bracket be sure the the locating pin (see data sheet) is in the appropriate sheet metal slot. The shaft on these potentionmeters is freely rotating. Therefore, when attaching the beam to the potentiometer shaft you need to check the whole range of shaft motion for continuous resistance. I suggest adjusting the pot to 1/2 full resistance, then attach the knob to the potientiometer shaft with the wooden beam held in the horizontal position.
--
Be sure to use pliers to tighten the potentiometer on the bracket.
-- Use a 1/16 hex wrench to tighten the knob onto the shaft.
Hot gluing the knob to the potentiometer will cost you 20 points on the lab.
- Solder three wires (from ribbon cable) to the potentiometer.
- Figure out how to put a rotation-stop on the beam so that the beam cannot go past vertical.
I suggest a piece of wire, or a coffee stir-stick or a drinking straw. One of my favorites from last
year is below. Plastic fork from Mattens.
Data Display
The DAC A/B channels will display beam angle and motor control on the scope. This will be useful for debugging and is required for the demo and the writeup. The top trace is the actual beam angle. You will note that the PID algorithm is poorly tuned in this image. There is an initial jump when the PIC32 is turned on with the beam hanging straight down, followed by oscillating convergence to the horizontal position. The bottom trace is the motor control signal used to drive the PWM. If you use a very large derivitive term in the PID controller to stabilize the oscillations, you may need to lowpass filter the motor signal to display on the scope. I used a first order IIR, digital lowpass, with a time constant of about 16 PWM samples, given by:
motor_disp = motor_disp + ((pwm_on_time - motor_disp)>>4);
Week one required checkpoint:
By the end of lab session in week one of the lab you must have:
- The mechanical assembly finished and be able to control motor speed open loop, from the PWM output.
- Oscilloscope display of the actual beam angle, and the low-passed motor command signal,
using the two channel DAC, as desribed below.
- Finishing a checkpoint does NOT mean you can leave lab early!
Week two required checkpoint:
By the end of lab session in week one of the lab you must have:
- Full closed-loop control of the motor.
- Serial command interface to set PID parmeters.
- Finishing a checkpoint does NOT mean you can leave lab early!
Week three Assignment
Write tasks using ProtoThreads, plus an ISR, and construct a circuit which will:
- Measure the angle of the beam supporting the lift-motor.
- Format the set angle and PID parameters to display appropriate messages on an LCD.
- At any time, take commands from the PC keyboard to:
- Set the desired beam angle.
- Set the PID proportional gain.
- Set the PID differential gain.
- Set the PID integral gain.
- To enter values on the PC keyboard, you will use command formats like:
- The new value takes effect immediately.
- One set of coefficients should produce stable behavior over the range of desired hover angles.
- Use a PID algorithm to control the speed of the motor by producing a PWM drive to the optoisolator. PWM setup example.
- Tune the PID algorithm so that you can change the angle of the beam quickly
and accurately without excessive angle oscillations.
- The user should be able to
enter a desired hover angle and the motor should quickly change the beam to the new angle.
The initial angle of the beam should be around -1.57 radian (hanging straight down).
- Display the motor control value (not the raw PWM signal) on the scope using channel B of the DAC.
Noise control on this signal is essential. If you cannot see the shape of the control signal, you will not
not get credit for this feature!
You may need to combine DSP and analog filtering, depending on exactly how
you build the circuit.
- Display the actual beam angle, from the angle sensor, on the scope using channel A of the DAC.
If this signal is noisy, you need to find out why! Poor wire routing, loose connections, and motor noise are
all possibilities. A noisy input makes the control PID algorithm very hard to tune.
- When a button is pushed (not the reset button), the beam should go through a
quick sequence of defined angle changes, using the current set of PID parameters:
- Before time=0, while holding the button, the beam should be hanging vertically down (motor off).
- When the button is released at time=0, target angle should be set to horizontal.
- At time=5 seconds, target angle should be set to approximately 30 degrees above horizontal.
- At time=10 seconds, target angle should be set to approximately 30 degrees below horizontal.
- At time=15 seconds, target angle should be set to horizontal.
You will demo all the features above to your TA.
Your program should not need to be
reset during the demo.
Your written lab report should include the sections mentioned in the policy page, and :
- A schematic of the circuit you built.
- Scope screen dumps of typical two-trace: (1) motor-control and (2) actual angle.
Include the demo sequence of four angles.
- A summary of the accuracy of your measurements.
How accurately can you measure the angle?
- How you selected the three PID gains.
- What are the maximum/minimum angles that produce stable behavior for your PID gains?
- What are the settling times at different angles.
- A heavily commented listing of your code.
Copyright Cornell University
November 8, 2019