Skip to content
Snippets Groups Projects
Commit c9621dba authored by Austin Rohlfing's avatar Austin Rohlfing
Browse files

Merge branch '40-improve-documentation-for-parameter-identification' into 'master'

Improve documentation for parameter identification

See merge request !25
parents 56912513 67224ff6
No related branches found
No related tags found
1 merge request!25Improve documentation for parameter identification
# Measuring Battery Discharge Rate[^1]
## Average Battery Discharge Rate
When flying the quadcopter, the voltage of the attached battery decreases throughout flight,
which has nonnegligible effects on the motor output. Because of this, we want to be able
to form a model for how the battery discharges. The actual battery discharge pattern is nonlinear,
but a simple linearization puts our voltage approximation significantly closer than simply assuming
a constant voltage, so that is the approach that is currently used.
## Variables
- $`V_0`$ - Modeled initial battery voltage
- $`\delta_V`$ - Average battery discharge rate
- $`t_i`$ - Time of $`i^{\text{th}}`$ voltage measurement
- $`V_i`$ - Voltage value of $`i^{\text{th}}`$ measurement
- $`{\mathbf t}`$ - Column vector of all $`t_i`$
- $`{\mathbf V}`$ - Column vector of all $`V_i`$
## Measurement Process
1. Attach a multimeter to measure voltage in parallel with the quad's battery.
1. Set the throttle to a value where the quad is nearly (or barely) hovering (because of the multimeter wires, this is as close as we can safely get to approximating flight).
1. Regularly record time and voltage measurement pairs $`t_i`$ and $`V_i`$ (ideally this step is automated).
1. Use MATLAB to solve the overdetermined system $`\begin{pmatrix}{\mathbf 1} & {\mathbf t}\end{pmatrix}\begin{pmatrix}V_0 \\ \delta_V\end{pmatrix} = {\mathbf V}`$ with the script given below.
## MATLAB Script
The below script assumes that you have your time (as seconds) and voltage (as volts) samples ($`t`$ and $`V`$) as column vectors (if you don't, transpose them before continuing).
```matlab
% A is matrix [1 t];
A = [ones(size(t)), t];
% Least squares to solve system
x = A \ V;
% Extract results for V_0 and delta_V
V_0 = x(1)
delta_V = x(2)
% Plot the samples and linearization
close all; figure; hold on;
plot(t, V, 'bo');
plot(t, V_0 + delta_V*V);
xlabel('Time (s)'); ylabel('Batt. Voltage (V)');
hold off;
```
This should output the proper values for $`V_0`$ and $`\delta_V`$, as well as plot the samples against
the linearization so you can visualize the precision of the approximation.
[^1]: Adapted from Section 5.4 of Matthew Rich's graduate thesis "Model development, system identification, and control of a quadrotor helicopter"
# Measuring Equivalent Moment of Inertia[^1]
## Variables
- $`K_V`$ - Motor back-emf constant $`\left(\frac{\text{rad}}{Vs}\right)`$
- $`R_m`$ - Motor resistance $`(\Omega)`$
- $`K_Q`$ - Motor torque constant $`\left(\frac{Nm}{A}\right)`$
- $`\tilde J_r`$ - Equivalent moment of inertia $`(kg\;m^2)`$
- $`\tau`$ - Time constant of transient rotor response $`(s)`$
## Equivalent Moment of Inertia
In order to determine the response to a motor speed command, we need the combined moment of inertia for the rotor and the outer motor housing (the parts that spin).
Note that this value is for a single motor its axis of rotation, not for all four combined.
A larger moment of inertia corresponds to the rotor taking more time to reach its target angular velocity.
The transient response of a rotor to a step change in input command should be approximately a negative exponential decay, specifically one where
```math
\tau = R_mK_VK_Q\tilde J_r
```
## Measurement Options
The big-picture goal here is to measure the time constant of the rotor speed transition after a step change in input command
(which when plotted with angular velocity as function of time should look like a negative exponential decay).
The time constant is the time it takes the angular velocity to reach $`63.2\%`$ of its final value from its initial value.
This can then be plugged into the above equation and rearranged such that $`\tilde J_r = \frac{\tau}{R_mK_VK_Q}`$.
There are two[^1][^2] approaches that have been used in the lab in the past. The first is to record the sound of rotors spinning,
view the spectrogram of the sound with MATLAB (the sound should transition to a higher pitch at higher rotor speeds), and measure the time constant.
This is done by the approximation that the time that the rotor takes to reach $`95\%`$ of its final velocity (pitch) is equal to $`3\tau`$.
The other option is to continuously measure angular velocity with a photointerrupter or optical tachometer, from which data can be used to determine the
actual time when the velocity crosses the $`63.2\%`$ threshold. Note that past time constants have been on the order of $`10^{-2}`$s, so if this approach is used,
the setup has to be able to take sufficiently fast samples.
## Procedure
1. Disable gyroscope feedback and secure or arrange the quadcopter so that it will not move when thrust is applied
1. Set up the chosen measurement device to be recording data
1. Apply an initial (non-zero) throttle command to the quadcopter
1. After a few seconds, step the throttle input to a larger value (there should be a fairly significant difference in the two command values)
1. After a few more seconds, return the throttle to 0 and stop recording data
1. Using the *Measurement Options* Section above, compute the time constant and moment of inertia
[^1]: Adapted from subsection 5.5.5 of Matthew Rich's graduate thesis "Model development, system identification, and control of a quadrotor helicopter"
[^2]: The photointerrupter approach can be found in subsection 6.4.4 of Ian McInerney's graduate thesis "Development of a multi-agent quadrotor research platform with distributed computational capabilities"
\ No newline at end of file
# Measuring Moment of Inertia[^1]
## Bifilar Pendulum
A bifilar pendulum consists of a mass affixed to a pair of vertical wires.
An angular displacement in the plane perpendicular to the wires creates an oscillation that is characterized by the moment of inertia of the mass.
We can measure this oscillation to determine the moments of intertia of the quadcoopter
about all three axes.
## Variables
- $`\theta`$ - Angular position relative to equilibrium
- $`J`$ - Moment of inertia
- $`D`$ - Distance between the wires
- $`m`$ - Mass of the quadcopter
- $`h`$ - Height of wire attachment from quadcopter center of mass
- $`\omega_n`$ - Frequency of oscillations
## Computing the Moment of Inertia
1. Suspend the quadcopter from a pair of wires to form a bifilar pendulum such that the $`z`$-axis of the quad is vertical
1. Introduce and angular displacement (around the vertical axis) to the quadcopter
1. Repeatedly measure the angular position with the VRPN camera system over a number of oscillations
1. Use MATLAB to compute the average frequency of the oscillations, $`\omega_n`$, and use it to compute the moment of inertia from the equation[^2] $`J_{zz} = \frac{mgD^2}{4h\omega_n^2}`$
1. Repeat for the $`x`$- and $`y`$-axes to compute $`J_{xx}`$ and $`J_{yy}`$
## Notes on Setup
- The wires should set up to be parallel (i.e. vertical, so the spacing between them on the quad matches the space where they are affixed above)
- The center of mass should be positioned halfway in between the two wires
- The value of $`D`$ can affect the precision and stability of the measurement, so try spacing the wires differently if the measurements seem inaccurate
- The value of $`h`$ should be maximized for best results, so it is recommend to affix the top of the wires as close to the ceiling as possible
[^1]: Adapted from Section 6.3 of Ian McInerney's graduate thesis "Development of a multi-agent quadrotor research platform with distributed computational capabilities"
[^2]: The derivation of this is shown in part in [this][matlab] article about computing moment of inertia measurements with MATLAB, which also contains some details regarding implementation
[matlab]: https://www.mathworks.com/company/newsletters/articles/improving-mass-moment-of-inertia-measurements.html
# Measuring Thrust and Drag Constants[^1]
## Introduction
For proper modeling of the quadrotor we need to go through the identification process.
This involves measuring parameters of the specific quadrotor in use, including both the thrust and drag constants.
This document describes the setup and procedure for measuring the thrust and drag constants of a quadrotor.
## Setup
The materials required are the following:
* Function generator
* Power supply capable of outputting ~30A
* Digital scale
* Optical tachometer
* Quadrotor
The first thing needed is to set the quadrotor onto the scale facing upside down.
This directs the force generated by the quad directly onto the scale
(note that you may need to place an object in between the quad and the scale to eliminate the possibility of a rotor hitting the scale).
After this is done the scale needs to be zeroed out so that the only force being measured is produced by the quads thrust.
Next we need to power the quad with the power supply.
This will replace the LiPO battery so that we can accurately measure the voltage being supplied at all times.
The voltage from the power supply should be ~12V.
The next step is to connect the ESC[^2] signal lines to the function generator to produce a known PWM output.
This PWM output has the following characteristics:
* $`f`$ = 400 Hz Square Wave
* $`V_{pp}`$ = 3.2 V
* $`V_{\text{offset}}`$ = 1.6 V
* Needs a duty cycle of 40% (1 millisecond pulse width) to initialize the ESCs
In the case that the onboard ESCs have changed,
the frequency and duty cycle required for initialization may change.
Simply reference the ESC documentation for the compatible signal frequencies
and choose a frequency within that range.
From there the calculation of the duty cycle for initialization,
denoted by $`P_{\text{min}}`$, is as follows:
```math
P_{\text{min}} = 0.001f
```
To calculate the maximum duty cycle that the ESC can handle, denoted by $`P_{\text{max}}`$, we use the following equation:
```math
P_{\text{max}} = 0.002f
```
These ESC signal lines are connected to a ribbon cable,
which then connects to the zybo board
through an insulation-displacement connector (IDC).
The function generator inputs go directly to the ESC
through this IDC connector and ribbon cable.
The pinout of the IDC connector is as follows:
| Pin 1[^3] | Pin 3 | Pin 5 | Pin 7 | Pin 9 | Pin 11 |
|:---------:|:-----:|:-----:|:-----:|:------:|:------:|
| Pin 2 | Pin 4 | Pin 6 | Pin 8 | Pin 10 | Pin 12 |
| Pin Number | Purpose |
|:----------:|:-----------------------|
| Pin 1 | Throttle |
| Pin 2 | ESC 0 signal line |
| Pin 3 | Aileron |
| Pin 4 | ESC 1 signal line |
| Pin 5 | Elevator |
| Pin 6 | ESC 2 signal line |
| Pin 7 | Rudder |
| Pin 8 | ESC 3 signal line |
| Pin 9 | Ground RC Receiver |
| Pin 10 | Ground |
| Pin 11 | Not used |
| Pin 12 | $`V_{cc}`$ RC Receiver |
After the ESC signal lines are properly connected
and the ESCs are being properly powered by the power supply,
we can begin collecting data.
## Data Collection
The first thing we need to do is increase the duty cycle of the function generator
from the calculated initialization value until the motors begin to turn.
We will denote this duty cycle value as $`P_i`$ for reference.
If the rotors do not begin to turn,
verify that the wave being sent from the function generator is correct
and that the ESCs are being powered properly from the power supply.
The data collection process is as follows:
1. Increase the input duty cycle by 1% (starting at $`P_i`$) and record its current value.
1. Using the optical tachometer, record the approximate steady state speed reached by each motor/rotor in RPM.
1. Record the corresponding input voltage from the power supply.
1. Record the corresponding digital scale reading in grams.
1. Record the current draw from the power supply.[^4]
1. Repeat 1-5 until reaching $`P_{\text{max}}`$.
To utilize the later provided MATLAB scripts to analyze the collected data and calculate the thrust and drag constants, the data needs to be stored in a specific way. Firstly, Excel should be used for storing the data. The required header layout of this Excel file should be as follows:
|Duty Cycle|Rotor 0 RPM|Rotor 1 RPM|Rotor 2 RPM|Rotor 3 RPM|Voltage|Scale Reading|Current|
|:--------:|:---------:|:---------:|:---------:|:---------:|:-----:|:-----------:|:-----:|
This is due to the fact that the functions created for calculating
the thrust and drag constants take in data as a table data type in MATLAB.
How these functions access the data in this table
is through specific indexing shown below
|Index 1|Index 2|Index 3|Index 4|Index 5|Index 6|Index 7|Index 8|
|:-----:|:-----:|:-----:|:-----:|:-----:|:-----:|:-----:|:-----:|
where each index value corresponds to its respective header.
Therefore, the name of the header doesn’t matter
as long as its associated data is in the same column as its referenced index.
## MATLAB Functions and Script
### Calculate Thrust Constant Function
```matlab
function [ Kt ] = calc_thrust_constant( data )
%CALC_THRUST_CONSTANT
% Calculates the thrust constant (Kt) given experimental data. The thrust
% constant is described in detail in sections 4.2.1.1 and 5.5.1 of
% "Model development, system identification, and control of a quadrotor
% helicopter" by Matt Rich.
% Input Arguments:
% data: experimental data
% Convert RPM to angular speed of each rotor.
rotor_speed_0 = data.(2) * (pi/30);
rotor_speed_1 = data.(3) * (pi/30);
rotor_speed_2 = data.(4) * (pi/30);
rotor_speed_3 = data.(5) * (pi/30);
% Define the A matrix as the sum of each rotors speed squared.
A = (rotor_speed_0.^2 + rotor_speed_1.^2 + rotor_speed_2.^2 + rotor_speed_3.^2);
% Convert weight (g) to thrust force (N) by converting grams to kilograms and
% multiplying by the acceleration of gravity.
T = (data.(7)/1000)*9.8;
% Calculate the thrust constant (Kt) through the following least squares
% approximation: Kt = (A'A)^-1.*A'.*T as defined on page 65 of "Model
% development, system identification, and control of a quadrotor
% helicopter" (Matt Rich's Thesis).
Kt = ((A'*A)^(-1))*(A'*T)
end
```
### Calculate Drag Constant Function
```matlab
function [ Kd ] = calc_drag_constant( data, Pmin, Pmax, Rm, Kv, Kq, If )
%CALC_DRAG_CONSTANT
% Calculates the drag constant (Kd) given experimental data. The drag
% constant is described in detail in sections 4.2.5, 4.2.6, and 5.5.4.1
% of "Model development, system identification, and control of a
% quadrotor helicopter" by Matt Rich.
% Input Arguments:
% data: experimental data
% Pmax: Calculated maximum duty cycle of the function generators PWM wave that the ESC can % handle.
% Pmin: Calculated minimum duty cycle of the function generators PWM wave for initialization % of the ESC.
% Rm: Motor resistance
% Kv: Back-EMF constant of the motor
% Kq: Torque constant of the motor
% If: No-Load (friction) current of the motor
% Convert RPM to angular speed of each rotor.
rotor_speed_0 = data.(2) * (pi/30);
rotor_speed_1 = data.(3) * (pi/30);
rotor_speed_2 = data.(4) * (pi/30);
rotor_speed_3 = data.(5) * (pi/30);
% Refer to the sections described in the header of this function
% for a better understanding of what this loop is doing.
% u: Defined in section 4.2.5
% omega: vector of each rotors speed in rad/s
% A: column vector of each rotors speed squared
% b: Defined in section 5.5.4.1
% Kd_vector: Vector containing all experimental Kd values
for i = 1:length(rotor_speed_1)
u = ((data.(1)(i)/100) - Pmin)/(Pmax - Pmin);
omega = [rotor_speed_0(i), rotor_speed_1(i), rotor_speed_2(i), rotor_speed_3(i)];
A = omega'.^2;
b = ((u*data.(6)(i))/(Rm*Kq))-omega'/(Rm*Kq*Kv)-If/Kq;
Kd_vector(i) = ((A'*A)^(-1))*(A'*b);
end
% Calculate the average of the Kd_vector to obtain the drag constant.
Kd = sum(Kd_vector)/length(Kd_vector)
end
```
Note that the function for calculating the drag constant
is dependant upon the following motor parameters:
| Parameter | Units | Description |
|:---------:|:--------------------:|:---------------------------|
| $`R_m`$ | $`\Omega`$ | Motor Resistance |
| $`K_V`$ | $`\frac{rad}{V\,s}`$ | Back-emf constant |
| $`K_Q`$ | $`\frac{A}{N\,m}`$ | Torque constant |
| $`i_f`$ | $`A`$ | No-Load (friction) current |
### Script for Calculating both Thrust and Drag Constants
```matlab
% Import data as a table.
data = readtable(file location);
% Define Pmin and Pmax, as well as the motor parameters Rm, Kv, Kq, and If
Pmin = insert calculated Pmin value here;
Pmax = insert calculated Pmax value here;
Rm = insert Rm value here;
Kv = insert Kv value here;
Kq = insert Kq value here;
If = insert If value here;
% Call the calc_thrust_constant() function.
Kt = calc_thrust_constant(data);
% Call the calc_drag_constant() function.
Kd = calc_drag_constant(data, Pmin, Pmax, Rm, Kv, Kq, If);
```
[^1]: This document was written in October 2016 by Andy Snawerdt, Tara Mina, and Brendan Bartels.
[^2]: This document's specifications references the current ESCs onboard, which are the [DJI 30A opto](https://www.dji.com/en/index.php/ESC).
[^3]: Pin 1 is specified by a trinagle on the body of the IDC connector.
[^4]: This isn’t actually necessary for the thrust or drag constant calculations, however this information may be useful later on for power requirements of the rotors.
# Modeling Parameters
This table was moved from a Word document that was last pushed to Git on Feb 5, 2017.
If the date listed for "Last Updated" is this, then the actual update date may be before that.
If the same procedure or document is used for multiple consecutive parameters,
it is given for the first and listed as "same" for subsequent rows.
| Symbol | Nominal Value | Units | Brief Description | Last Updated | Measurement Procedure |
|:------------------------:|:-----------------------:|:-------------------------:|:--------------------------------------------------------------|:-------------|:----------------------|
| $`m_q`$ | $`0.986`$ | $`kg`$ | Quadcopter mass | Feb 5, 2017 | Measured with a scale |
| $`m_b`$ | $`0.204`$ | $`kg`$ | Battery mass | Feb 5, 2017 | same |
| $`m`$ | $`1.19`$ | $`kg`$ | Quadcopter + battery mass | Feb 5, 2017 | same |
| $`g`$ | $`9.81`$ | $`\frac{m}{s^2}`$ | Acceleration of gravity | [constant] | [constant] |
| $`J_{xx}`$ | $`0.0218`$ | $`kg\,m^2`$ | Quadrotor + battery moment of inertia around $`b_x`$ | Feb 5, 2017 | [Measuring Moment of Inertia][3] |
| $`J_{yy}`$ | $`0.0277`$ | $`kg\,m^2`$ | Quadrotor + battery moment of inertia around $`b_y`$ | Feb 5, 2017 | same |
| $`J_{zz}`$ | $`0.0332`$ | $`kg\,m^2`$ | Quadrotor + battery moment of inertia around $`b_z`$ | Feb 5, 2017 | same |
| $`J_{\text{req}}`$ | $`4.2012\times10^{-5}`$ | $`kg\,m^2`$ | Rotor + motor moment of inertia around motor axis of rotation | Feb 5, 2017 | [Measuring Equivalent Moment of Inertia][5] |
| $`K_T`$ | $`8.6519\times10^{-6}`$ | $`\frac{kg\,m}{rad^2}`$ | Rotor thrust constant | Feb 5, 2017 | [Measuring Thrust and Drag Constants][1] |
| $`K_d`$ | $`1.0317\times10^{-7}`$ | $`\frac{kg\,m^2}{rad^2}`$ | Rotor drag constant | Feb 5, 2017 | same |
| $`K_H`$ | | $`\frac{kg}{rad}`$ | Rotor in-plane drag constant | Feb 5, 2017 | _Matt's thesis 5.5.3, needs doc_ |
| $`\delta_{T_z}`$ | | $`\frac{kg}{rad}`$ | Rotor velocity thrust adjustment factor | Feb 5, 2017 | _Matt's thesis 5.5.2, needs doc_ |
| $`\lvert r_{h_x}\rvert`$ | $`0.16`$ | $`m`$ | $`x`$-axis distance from center of mass to a rotor hub | Feb 5, 2017 | Measure by hand |
| $`\lvert r_{h_y}\rvert`$ | $`0.16`$ | $`m`$ | $`y`$-axis distance from center of mass to a rotor hub | Feb 5, 2017 | same |
| $`\lvert r_{h_z}\rvert`$ | $`0.03`$ | $`m`$ | $`z`$-axis distance from center of mass to a rotor hub | Feb 5, 2017 | same |
| $`R_m`$ | $`0.2308`$ | $`\Omega`$ | Motor resistance | Feb 5, 2017 | [Measuring Motor Resistance][2] |
| $`K_Q`$ | $`96.3422`$ | $`\frac{A}{N\,m}`$ | Motor torque constant | Feb 5, 2017 | Specified by motor |
| $`K_V`$ | $`96.3422`$ | $`\frac{rad}{V\,s}`$ | Motor back-emf constant | Feb 5, 2017 | Specified by motor |
| $`i_f`$ | $`0.511`$ | $`A`$ | Motor internal friction (no-load) current | Feb 5, 2017 | Remove rotor and measure with power supply and ammeter |
| $`P_\bot`$ | $`117000`$ | [none] | ESC turn-on duty cycle command | Feb 5, 2017 | [Measuring Thrust and Drag Constants][1] |
| $`P_\bot`$ | $`100000`$ | [none] | Minimum Zybo output duty cycle command | Feb 5, 2017 | |
| $`P_\top`$ | $`100000`$ | [none] | Maximum Zybo output duty cycle command | Feb 5, 2017 | |
| $`\delta_V`$ | | $`\frac{V}{s}`$ | Approximate constant battery discharge rate | Feb 5, 2017 | [Measuring Battery Discharge Rate][4] |
| $`T_C`$ | $`0.01`$ | $`s`$ | Camera system sampling period | Feb 5, 2017 | |
| $`\tau_C`$ | | $`s`$ | Camera system total latency | Feb 5, 2017 | |
* 0.175 ms single trip latency between camera system and ground station (ping)
[1]: MeasuringThrustAndDragConstants.md
[2]: ../controls/documentation/MeasuringMotorResistance.pdf
[3]: MeasuringMomentOfInertia.md
[4]: MeasuringBatteryDischarge.md
[5]: MeasuringEquivMoment.md
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment