Moment of Inertia (J) and Damping (C)

How to determine the J and C parameters of the servo via a pendulum setup.

The setup for finding the moment of inertia (J) and the damping (C) are largely the same, and will be covered in this portion of the guide. This guide will use a pendulum setup to find the desired properties.

The Math Behind the Pendulum Setup

To briefly explain how this process will work, the equation of motion (EoM) for an unpowered pendulum oscillating is:

Jsystemθ¨+csystemθ˙+ksystemθ=0J_{system}\ddot\theta+c_{system}\dot\theta+k_{system}\theta =0

For a setup where a servomotor forms the pivot point for the pendulum, different portions of these properties will be contributed by the servo and by the pendulum. Thus, the EoM becomes:

(Jservo+Jpend)θ¨+cservoθ˙+(kservo+kpend)θ=0(J_{servo}+J_{pend})\ddot\theta+c_{servo}\dot\theta+(k_{servo}+k_{pend})\theta =0

The pendulum properties can be easily calculated based on the overall length and mass of the pendulum:

Jpend=mpendLpend2J_{pend} = m_{pend}L_{pend}^2

kpend=gmpendLpendk_{pend} = g*m_{pend}L_{pend}

Additionally, the EoM simplifies based on the status of the servo. When the motor inside the servo is not powered, functionally only the moment of inertia inherent to the coiling of the motor is present. There may be some slight damping from the coils, but it should be basically negligible. Thanks to the robust internal workings of the Dynamixel, we can create this state while still monitoring other portions of the servo by disabling torque. Thus, the equation of motion for the unpowered (torque disabled) servo is:

(Jservo+Jpend)θ¨+kpendθ=0(J_{servo}+J_{pend})\ddot\theta+k_{pend}\theta = 0

If the motor is powered inside the servo, then the motor provides some degree of damping. However, it will not provide any stiffness unless it is given a commanded position. This is because the control board in the servo artificially provides the stiffness through software by changing the gain of the PID loop. Without a commanded position, the PID loop is not involved, so there is no stiffness provided by the servo.

Thus, the equation of motion for the powered (torque enabled) servo not given a commanded position is:

(Jservo+Jpend)θ¨+cservoθ˙+kpendθ=0(J_{servo}+J_{pend})\ddot\theta+c_{servo}\dot\theta+k_{pend}\theta = 0

To recap this information, because it's crucial to the entire process:

Servo State

Resulting Properties

Torque disabled

JservoJ_{servo}

Torque enabled, no commanded position

JservoJ_{servo}

cservoc_{servo}

Torque enabled, commanded position set

JservoJ_{servo}

cservoc_{servo}

kservok_{servo}

However, this does not help establish what each of these properties actually are. To do that, we must consider several directly observable variables that describe a pendulum's oscillatory motion. These variables are then related to different properties of the setup. Most crucial for this process are:

Natural Frequency:

ωn=1Tn=ksystemJsystem=kservo+kpendJservo+Jpend\omega_n= \frac{1}{T_n}=\sqrt{\frac{k_{system}}{J_{system}}} = \sqrt{\frac{k_{servo}+k_{pend}}{J_{servo}+J_{pend}}}

where TnT_n is the natural period (the time to complete a full cycle of motion)

Damped Natural Frequency:

ωd=ωn1ζ2\omega_d = \omega_n\sqrt{1-\zeta^2}

Logarithmic Decrement:

δ=lnx1x2=2πcservoωd2m\delta = \ln{\frac{x_1}{x_2}} = \frac{2\pi c_{servo}}{\omega_{d} *2 m}

where x1 and x2 are the height of two adjacent peaks:

From Wikipedia

Damping Ratio:

ζ=δ(2π)2+δ2\zeta = \frac{\delta}{\sqrt{(2\pi)^2+\delta^2}}

Based on these properties, we can derive JservoJ_{servo} and cservoc_{servo} based on the oscillation recorded from the pendulum.

The Pendulum Setup

An example setup for the damping tests

An example of the pendulum setup is pictured above. It's essentially just the servo bracketed to the bottom of a sheet of polycarbonate. The main considerations for the setup are as follows:

  1. Use an 80-20 beam to ensure that the polycarbonate doesn't flex during the runtime

  2. Use 80-20 beams butting up against the servo on either side to minimize the amount that the servo can vibrate side-to-side during runtime. This is mostly crucial for the damping tests.

  3. The Arduino code for the test setup is designed so that the servo has ID 01.

  4. The weight used for the tests will change based on the desired parameter. For the inertia tests, use the smallest possible weight to minimize JpendJ_{pend}. JservoJ_{servo} will be fairly small, so minimizing JpendJ_{pend}will increase your accuracy in measuring JservoJ_{servo}. For the damping tests, the torque being enabled makes the pendulum much harder to deflect from equilibrium. To maximize the number of times the pendulum will oscillate (and thus the number of peaks to analyze), use the largest weight possible at the end of the pendulum. The pendulums that are currently in the lab, and their properties, are listed and shown below:

Above is each style of lever arm for J and C tests. The second to right-most lever arm can accommodate 2000 or 4000 grams.

Included Mass (g)

Total Mass (g)

Functional Length (from servo axis to CoM) (in)

Best Used For

500

549.3

10.21

J Tests

1000

1071.22

11.43

--

2000

2064.7

11.63

C Tests

2000

2154

24.25

--

4000

4148.4

25.25

C Tests

4000

4994

37.43

C Tests

CAD Files

CAD files for each part of the pendulum setup for the MX-28s, as well as a full setup assembly

Taking Data

Using the Arduino interface, it is possible to read the position of the servo motor output shaft. The code below can be used for the MX28, MX64 and XM540 servo motors given a few parameters are changed for each use type. The addresses of key parameters are shown in the table below.

Model Number
Address Line
Value

MX28/MX64

ADDR_AX_TORQUE_ENABLE

24

ADDR_AX_PRESENT_POSITION

36

ADDR_AX_GOAL_POSITION

30

XM540

ADDR_AX_TORQUE_ENABLE

64

ADDR_AX_PRESENT_POSITION

116

ADDR_AX_GOAL_POSITION

132

#include <DynamixelSDK.h>

// AX-series Control table address
#define ADDR_AX_TORQUE_ENABLE           24
#define ADDR_AX_PRESENT_POSITION        36
#define ADDR_AX_GOAL_POSITION           30

#define PROTOCOL_VERSION                1.0

#define DXL_ID                          1
#define BAUDRATE                        1000000
#define DEVICENAME                      "1"

#define TORQUE_ENABLE                   1                   // Value for enabling the torque
#define TORQUE_DISABLE                  0

#define ESC_ASCII_VALUE                 0x1b

void setup() {
  // put your setup code here, to run once:
  Serial.begin(115200);
  while(!Serial);

  Serial.println("Start..");

  dynamixel::PortHandler *portHandler = dynamixel::PortHandler::getPortHandler(DEVICENAME);
  dynamixel::PacketHandler *packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION);
  int index = 0;
  int dxl_comm_result = COMM_TX_FAIL;
  unsigned long t = 0;
  int dxl_goal_position = 300;

  uint8_t dxl_error = 0;
  int16_t dxl_present_position = 0;
  

  pinMode(BOARD_BUTTON_PIN, INPUT_PULLDOWN);
  pinMode(BOARD_LED_PIN, OUTPUT);

  // Open port
  if (portHandler->openPort())
  {
    Serial.print("Succeeded to open the port!\n");
  }
  else
  {
    Serial.print("Failed to open the port!\n");
    Serial.print("Press any key to terminate...\n");
    return;
  }

  // Set port baudrate
  if (portHandler->setBaudRate(BAUDRATE))
  {
    Serial.print("Succeeded to change the baudrate!\n");
  }
  else
  {
    Serial.print("Failed to change the baudrate!\n");
    Serial.print("Press any key to terminate...\n");
    return;
  }

  dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL_ID, ADDR_AX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error);
  if (dxl_comm_result != COMM_SUCCESS)
  {
    packetHandler->getTxRxResult(dxl_comm_result);
    Serial.print("Dynamixel");
    Serial.print(DXL_ID);
    Serial.print("has NOT connected \n");
  }
  else if (dxl_error != 0)
  {
    packetHandler->getRxPacketError(dxl_error);
    Serial.print("Dynamixel ");
    Serial.print(DXL_ID);
    Serial.print("has NOT connected \n");
  }
  else
  {
    Serial.print("Dynamixel ");
    Serial.print(DXL_ID);
    Serial.print("has been successfully connected \n");
  }
  while(digitalRead(BOARD_BUTTON_PIN)==LOW);

  while(1){

    int ch;

    ch = Serial.read();
    if( ch == 'q' )
      break;
      
    dxl_comm_result = packetHandler->read2ByteTxRx(portHandler, DXL_ID, ADDR_AX_PRESENT_POSITION, (uint16_t*)&dxl_present_position, &dxl_error);
      if (dxl_comm_result != COMM_SUCCESS)
      {
        packetHandler->getTxRxResult(dxl_comm_result);
      }
      else if (dxl_error != 0)
      {
        packetHandler->getRxPacketError(dxl_error);
      }
  t = millis();
  Serial.print(t);
  Serial.print("\t");
  Serial.print(dxl_present_position);
  Serial.println(" ");
  }
}

void loop() {
  // put your main code here, to run repeatedly:


}
  1. After restarting the board, open the Serial Monitor (top right corner) in Arduino to begin the program. The program will tell you the connection status of the servo. If you see, "Dynamixel 1 has NOT connected", restart the program.

  2. For a J test: Grab the pendulum and move it to the highest point for the run. This point can be in either direction.

    For a c test: The pendulum will be much harder to move with the torque enabled. Pull the pendulum slightly, until you feel the most resistance. This will probably only be a >10^{\circ} movement at most.

  3. Press the circular button in the OpenCM to begin reading position data from the servo, then let go of the pendulum.

  4. Allow the pendulum to oscillate until it stabilizes, then send 'q' in the Serial Monitor to halt the position data.

  5. Copy all of the data from the Serial Monitor and paste it into Notepad. Delete the first few lines of text so it's just data, then save the file using the following name convention for use with the MATLAB code that will presenting in the next section:

Trial Type

File Naming Convention

Example

Inertia (J)

NoTNoPos<mass in kg>_<length in inches>_Trial<number>.txt

NoTNoPos_0.5kg_12.5 in_Trial1.txt

Damping (C)

YesTNoPos_<mass in kg>_<length in inches>_Trial<number>.txt

YesTNoPos_2kg_12.5in_Trial1.txt

Trials for J tests and C tests should be in different folders. If you have multiple sets of trials that you want to remain separate (for example, from different days or from slightly different setups), put them in separate folders and restart the trial numbering for each folder. For example, I have folders for tests taken on 6.22.21 and 6.24.21. There is a 'NoTNoPos_0.5kg_12.5in_Trial1.txt' file in each of these folders.

You are also free to organize your files another way, but this way ensures the most seamless integration with the MATLAB code in the next section.

To switch between data collection for an inertia trial and a damping trial, change the TORQUE_ENABLE value in line 64 of the code to TORQUE_DISABLE.

Parsing Data

I have developed MATLAB code to determine the waveform properties for each trial , then use the mean of these values to find J and C. This code involves two files.

processPendv2.m

%Clarissa Goldsmith
%West Virginia University
%6/18/21

function [dampedFreq, logDec, posRad, t,fig] = processPendv2(fileTree,fileName)
%% 
% close all
% clear all

%------ Import the data
data = importdata(fileTree);
posRaw = data(:,2);
posRaw = posRaw - mean(posRaw(end-100:end)); %Normalize the position based on the mid-point of the servos
t = data(:,1)/1000;
t = t - t(1); %Normalize the time

%------ Get rid of the weird 1 position outliers throughout
posF(1) = posRaw(1); 
for i=2:1:length(posRaw)-1
    if posRaw(i-1) == posRaw(i+1)
        if abs(posRaw(i+1)-posRaw(i)) < 2
            posF(i) = posRaw(i+1);
        end
    else
        posF(i)= posRaw(i);
    end
end
posF(length(posRaw)) = posRaw(end);

%------ Smooth the filtered data
posFSm = smooth(t,posF,10);

%------ Get rid of the flat portion on the front of the data
frontFlat = 0;
i = 1;
while frontFlat == 0
    if abs(posFSm(i+100)-posFSm(i)) > 5
        posFSm = posFSm(i:end);
        t = t(i:end);
        frontFlat = 1;
    else
        posFSm = posFSm(i+100:end);
        t = t(i+100:end);
    end
    %plot(t,posFSm)
    i = i+1;
end

%------ Convert to radians
posFSmDeg = posFSm*0.088;
posRad = posFSmDeg*pi/180;

%% ------ Find peaks
%------ Determine if the first peak is a min or a max
posPeaks = posRad;
if posRad(1) > 0
    peakSign = 0; %Where 0 = - = min and 1 = + = max
else
    peakSign = 1;
end

peaks = [];
finding = 1;
j=1;
i = 1;
peakTol = 0.02;
instPeak = 0;

%------ Start finding peaks
while finding == 1
    if peakSign == 0 %Peak is a minimum
        peakVal = min(posPeaks);
        peakSign = 1;
    else %Peak is a maximum
        peakVal = max(posPeaks);
        peakSign = 0;
    end

        %Find everywhere that the data hits that peak value
        if ~isempty(peaks)
            peakApprox = find(peakVal-0.000001 < posPeaks & posPeaks < peakVal+0.000001) + peaks(end);
        else
            peakApprox = find(peakVal-0.000001 < posPeaks & posPeaks < peakVal+0.000001) + instPeak;
        end
        
        %Check if there are any weird outliers (they should all be roughly
        %sequential)
        outlier = 1;
        while outlier == 1
            if length(peakApprox)== 1
                outlier = 0;
            else
                peakL = length(peakApprox);
                peakLMid = round(peakL/2);
                if peakApprox(1)+ peakLMid + 2 < peakApprox(peakLMid) || peakApprox(end) - peakLMid - 2 > peakApprox(peakLMid)
                    if peakApprox(1)+ peakLMid + 2 < peakApprox(peakLMid)
                        peakApprox = peakApprox(2:end);
                    else
                        peakApprox = peakApprox(1:end-1);
                    end
                else
                    outlier = 0;
                end
            end
        end
        
        if abs(peakVal) <= 0.5
            %The peak position will be in the middle of the values found by
            %peakApprox
            peaks(j) = round(peakApprox(1) + (peakApprox(end)-peakApprox(1))/2);
            %Then cut the data we consider for the peaks so we don't find that peak
            %again
            posPeaks = posRad(peaks(j):end);
            tPeaks = t(peaks(j):end);
            j = j + 1;
            i = i +1;
            %Check if we've basically reached equilibrium
            if abs(peakVal) < peakTol 
                %Cut the data here to get rid of the flat bit at the end
                if peaks(end) > peaks(end-1)
                    posRad = posRad(1:peaks(end));
                    t = t(1:peaks(end));
                else
                    posRad = posRad(1:peaks(end-1));
                    t = t(1:peaks(end-1));
                end
                    peaks = peaks(1:end-1);
                    finding = 0;
            end
        else
            instPeak = round(peakApprox(1) + (peakApprox(end)-peakApprox(1))/2);
            posPeaks = posRad(instPeak:end);
            tPeaks = t(instPeak:end);
            i = i+1;
        end

end



%% ------ Extract servo properties based on data
if length(peaks) <= 2
    warning('Error: Not enough peaks for calculation');
    T_damp = 0;
    omega_damp = 0;
    zeta_raw = 0;
    omega_nat_raw = 0;
    delta = 0;
else
    for i=1:length(peaks)-2
        dampedPer(i) = (t(peaks(i+2)) - t(peaks(i)));
        dampedFreq(i) = (2*pi)/dampedPer(i);
        logDec(i) = log(abs(posRad(peaks(i)))/abs(posRad(peaks(i+1))));
        dampRat(i) = logDec(i)/sqrt((2*pi)^2+logDec(i)^2);
        natFreq(i) = dampedFreq(i)/sqrt(1-dampRat(i)^2);
    end
    %Take the average of the parameters found via the peaks to get the usable
    %values
    T_damp = mean(dampedPer);
    omega_damp = mean(dampedFreq);
    zeta = mean(dampRat);
    omega_nat = mean(natFreq);
    delta = mean(logDec);
end

%% Find the best fit curve

%-- Best fit with 1 variable
% start = zeta_raw;
% y0 = posRad(1);
% charEq = @(zeta) y0 * (exp(-zeta*omega_nat*(t-t(1))).*cos((omega_nat*sqrt(1-zeta^2))*(t-t(1)))); 
% LSeq = @(zeta) sum((posRad-charEq(zeta)).^2);
% %options = optimoptions(@fminunc, 'OptimalityTolerance',1e-10,'Display','off');
% [zeta,~] = fminunc(LSeq,start);
% omega_damp = omega_nat*sqrt(1-zeta^2);

%-- Best fit with 2 variables
% start = [zeta_raw, omega_nat];
% y0 = posRad(1);
% charEq = @(x) y0 * (exp(-x(1)*x(2)*(t-t(1))).*cos((x(2)*sqrt(1-x(1)^2))*(t-t(1)))); 
% LSeq = @(x) sum((posRad-charEq(x)).^2);
% %options = optimoptions(@fminunc, 'OptimalityTolerance',1e-10,'Display','off');
% [vals,~] = fminunc(LSeq,start);
% omega_nat = vals(2);
% zeta = vals(1);
% omega_damp = omega_nat*sqrt(1-zeta^2);

%% --- Plot shit
%------ Plot the peaks and the tolerance lines to check on things

fig = tiledlayout(2,3);
title(fig,fileName,'Interpreter', 'none');
nexttile(1,[1,3])
plot(t,posRad);
hold on
plot(t(peaks),posRad(peaks),'o')  
yline(peakTol,':','Color',[0.4 0.4 0.4]);
yline(-peakTol,':','Color',[0.4 0.4 0.4]);
yline (0.5, ':','Color',[0.4 0.4 0.4]);
yline (-0.5, ':','Color',[0.4 0.4 0.4]);
yline (0, '--k');
ylabel('Position (rad)');
xlabel('Time (s)');
%plot(t,charEq(vals));

%------ Plot all of the values over the peaks to see the variance
%Damped Period
nexttile
plot(dampedPer,'-o')
title('Damped Period'); 
d = 2;

perPlotMin = round(min(dampedPer),d, 'significant');
perPlotMax = round(max(dampedPer),d, 'significant'); 
if perPlotMax < max(dampedPer)
    perPlotMax = max(dampedPer);
elseif perPlotMin > min(dampedPer)
    perPlotMin = min(dampedPer);
end
if perPlotMax == perPlotMin
    perPlotMax = perPlotMax + 0.1;
end
axis([1 (length(peaks)-2) perPlotMin perPlotMax]);
grid on
yline(T_damp,'--');
xlabel(append('Averaged Value: ', num2str(T_damp))) 

%Damping Ratio
nexttile
plot(dampRat, '-o');
title('Damping Ratio')
grid on
dampRatPlotMin = round(min(dampRat),d, 'significant');
dampRatPlotMax = round(max(dampRat),d, 'significant'); 
if dampRatPlotMax == dampRatPlotMin
    dampRatPlotMax = dampRatPlotMax + 10^-(d);
end
if dampRatPlotMin > min(dampRat)
    dampRatPlotMin = dampRatPlotMin - 10^-(d);
end
if dampRatPlotMax < max(dampRat)
    dampRatPlotMax = dampRatPlotMax + 10^-(d);
end
axis([1 (length(peaks)-2) dampRatPlotMin dampRatPlotMax]);
yline(zeta,'--');
xlabel(append('Averaged Value: ', num2str(zeta)));

%Frequencies

nexttile
plot(dampedFreq, '-o');
hold on
plot(natFreq,'-o');

title('Frequencies')
grid on
freqPlotMin = min(round(min(natFreq),d, 'significant'),round(min(dampedFreq),d, 'significant'));
if freqPlotMin > min(natFreq)
    freqPlotMin = freqPlotMin - 10^-(d-1);
elseif freqPlotMin > min(dampedFreq)
    freqPlotMin = freqPlotMin - 10^-(d-1);
end
freqPlotMax = max(round(max(natFreq),d, 'significant'),round(max(dampedFreq),d, 'significant')); 
if freqPlotMax < max(natFreq)
    freqPlotMax = freqPlotMax + 10^-(d-1);
elseif freqPlotMax < max(dampedFreq)
    freqPlotMax = freqPlotMax + 10^-(d-1);
end
if freqPlotMax == freqPlotMin
    freqPlotMax = freqPlotMax + 10^-(d-1);
end
axis([1 (length(peaks)-2) freqPlotMin freqPlotMax]);
yline(omega_damp,'--','Color',[0 0.4470 0.7410]);
yline(omega_nat,'--','Color',[0.8500 0.3250 0.0980]);
legend('Damped Frequency','Natural Frequency')
xlabel({append('Averaged Values: \omega_{damp} = ',num2str(omega_damp),', ','\omega_{nat} = ',num2str(omega_nat))})
%keyboard
end

This function is the main workhorse for parsing the raw data. Given the location data for a trial, it will spit out a cleaned up and converted version of the raw data, a figure showing the waveform, and a vector of all of the damped natural frequency and log decrement values it was able to calculate using subsequent peaks. The code should be commented to the point where it's function is pretty straightforward.

servoCharacteristicCalculator.m

This script essentially functions as follows:

  • Given the base file names for each type of trial, the file locations of the trials, and the number of trials in each location, call processPendv2 to process each trial

  • Collect a vector containing the damped natural frequencies ( ωd\omega_d ) and log decrements ( δ\delta ) from every set of peaks across all trials

  • Remove any outliers from the vectors

  • Take the mean of the vectors, then use the final ωd\omega_d and δ\delta values to calculate J and C.

  • Based on the maximum difference between the mean values of ωd\omega_d and δ\delta and the raw data, develop a sense of the uncertainty in the J and C values.

  • Display the J and C values in the command window with the calculated uncertainties.

%Clarissa Goldsmith
%West Virginia University
%6/18/21

clear all
close all

%------ CHANGE THESE VALUES
numJTrials = [10;10]; 
numCTrials = [0];
JFileNameBase = 'NoTNoPos_0.5kg_';
JFileLoc = {'C:\Users\clari\Documents\NeuroMINT\Matlab Programs\Servo Characterization\Trials\No Nylon Washer\J Trials\6.22.21',...
    'C:\Users\clari\Documents\NeuroMINT\Matlab Programs\Servo Characterization\Trials\No Nylon Washer\J Trials\6.24.21'};
CFileLoc = {'C:\Users\clari\Documents\NeuroMINT\Matlab Programs\Servo Characterization\Trials\No Nylon Washer\C Trials'};
CFileNameBase = 'YesTNoPos_2kg_';

%------ 
%For the J tests, use the 500g pendulum. For the c tests, use the 2000g
%pendulum.
JSetup.mass = (500+71.22)/1000; %In kg
CSetup.mass = (2000+71.22)/1000;

JSetup.length = 10.213*0.0254; %In m
CSetup.length = 11.6321*0.0254;


%------ Calculate J_pend and k_pend for both setups
JSetup.pendJ = JSetup.mass*JSetup.length^2;
CSetup.pendJ = CSetup.mass*CSetup.length^2;

JSetup.kPend = JSetup.mass*9.81*JSetup.length;
CSetup.kPend = CSetup.mass*9.81*CSetup.length;



%------ Process J trials (if any) and find values
tr = 0;
JOmegaDamp = [];
JDelta = [];
if norm(numJTrials) >= 1
    %------ Process the J trial with processPendv2
    for ii = 1:length(JFileLoc)
        for i=1:numJTrials(ii)
            tr = tr + 1;
            JFileName = append(JFileNameBase, 'Trial', string(tr));
            JFileTree = append(JFileLoc{ii}, '\', JFileName, '.txt');
            if isfile(JFileTree)
                figure
                [JTrials(tr).dampedFreq, JTrials(tr).logDec, JTrials(tr).pos, JTrials(tr).t, JTrials(tr).fig] = processPendv2(JFileTree,JFileName);
                JOmegaDamp = [JOmegaDamp JTrials(tr).dampedFreq];
                JDelta = [JDelta JTrials(tr).logDec];
            end
        end
    end
    %------ Check if there are any outlier property values and remove them
    %Basically checking if there are any bins in a histogram that would
    %contain less values than would have come out of one trial, then
    %removing them from consideration
    [omegaDN,omegaDEdges] = histcounts(JOmegaDamp);
    [deltaN,deltaEdges] = histcounts(JDelta);
    avgTrialVals = length(JDelta)*.1;
    outliers = 1;
    while outliers == 1
        if omegaDN(1) < avgTrialVals || omegaDN(end) < avgTrialVals || deltaN(1) < avgTrialVals || deltaN(end) < avgTrialVals
            if omegaDN(1) < avgTrialVals
                omegaDN = omegaDN(2:end);
                omegaDEdges = omegaDEdges(2:end);
                vals = find(JOmegaDamp < omegaDEdges(1));
                for i=1:length(vals)
                    JOmegaDamp(vals(i)) = NaN;
                    JDelta(vals(i)) = NaN;
                end
            end
            
            if omegaDN(end) < avgTrialVals
                omegaDN = omegaDN(1:end-1);
                omegDEdges = omegaDEdges(1:end-1);
                vals = find(JOmegaDamp > omegaDEdges(end));
                for i=1:length(vals)
                    JOmegaDamp(vals(i)) = NaN;
                    JDelta(vals(i)) = NaN;
                end
            end
            
            if deltaN(1) < avgTrialVals
                deltaN = deltaN(2:end);
                deltaEdges = deltaEdges(2:end);
                vals = find(JDelta < deltaEdges(1));
                for i=1:length(vals)
                    JOmegaDamp(vals(i)) = NaN;
                    JDelta(vals(i)) = NaN;
                end
            end
            
            if deltaN(end) < avgTrialVals
                deltaN = deltaN(1:end-1);
                deltaEdges = deltaEdges(1:end-1);
                vals = find(JDelta > deltaEdges(end));
                for i=1:length(vals)
                    JOmegaDamp(vals(i)) = NaN;
                    JDelta(vals(i)) = NaN;
                end
            end
        else
            outliers = 0;
        end
        JOmegaDamp = rmmissing(JOmegaDamp);
        JDelta = rmmissing(JDelta);
    end
    JZeta = 1./sqrt(1+((2*pi)./JDelta).^2);
    JOmegaNat = JOmegaDamp./sqrt(1-JZeta.^2);
   
    % Figure out error bars for J
    delJOmegaD = max(abs(mean(JOmegaDamp) - JOmegaDamp));
    delJDelta = max(abs(mean(JDelta) - JDelta));
    delJZeta = sqrt(((4*pi^2)/(((4*pi^2)/mean(JDelta)^2+1)^(3/2)*mean(JDelta)^3))^2*delJDelta^2);
    delJOmegaNat = sqrt((1/sqrt(1-mean(JZeta)^2))^2*(delJOmegaD)^2 + ((mean(JOmegaDamp)*mean(JZeta))/((1-mean(JZeta)^2)^(3/2)))^2*(delJZeta)^2);
    servoJ = JSetup.kPend/mean(JOmegaNat)^2 - JSetup.pendJ;
    delJ = sqrt(((2*JSetup.kPend)/mean(JOmegaNat)^3)^2*(delJOmegaNat)^2);
    disp(['Servo Moment of Inertia: ', num2str(servoJ), ' ',char(177), ' ', num2str(delJ), ' (', num2str(delJ/servoJ*100),'% error)'])
    
    % What if zeta was zero?
    servoJNoDamp = JSetup.kPend/mean(JOmegaDamp)^2 - JSetup.pendJ;
    delJNoDamp = sqrt(((2*JSetup.kPend)/mean(JOmegaDamp)^3)^2*(delJOmegaD)^2);
    disp(['With zeta = 0: ',num2str(servoJNoDamp), ' ',char(177), ' ', num2str(delJNoDamp) ' (', num2str(delJNoDamp/servoJNoDamp*100),'% error)']);
end

%------ Process c trials (if any) and find values
tr = 0;
COmegaDamp = [];
CDelta = [];
if norm(numCTrials) >= 1
    %------ Process the c trial with processPendv2
    for ii = 1:length(CFileLoc)
        for i=1:numCTrials(ii)
            tr = tr + 1;
            CFileName = append(CFileNameBase, 'Trial', string(i));
            CFileTree = append(CFileLoc{ii}, '\', CFileName, '.txt');
            if isfile(CFileTree)
                figure
                [CTrials(tr).dampedFreq, CTrials(tr).logDec, CTrials(tr).pos, CTrials(tr).t, CTrials(tr).fig] = processPendv2(CFileTree, CFileName);
                COmegaDamp = [COmegaDamp CTrials(tr).dampedFreq];
                CDelta = [CDelta CTrials(tr).logDec];
            end
        end
    end
    %------ Check if there are any outlier property values and remove them
    %Basically checking if there are any bins in a histogram that would
    %contain less values than would have come out of one trial, then
    %removing them from consideration
    [omegaDN,omegaDEdges] = histcounts(COmegaDamp);
    [deltaN,deltaEdges] = histcounts(CDelta);
    avgTrialVals = length(CDelta)/tr;
    outliers = 1;
    while outliers == 1
        if omegaDN(1) < avgTrialVals || omegaDN(end) < avgTrialVals || deltaN(1) < avgTrialVals || deltaN(end) < avgTrialVals
            if omegaDN(1) < avgTrialVals
                omegaDN = omegaDN(2:end);
                omegaDEdges = omegaDEdges(2:end);
                vals = find(COmegaDamp < omegaDEdges(1));
                for i=1:length(vals)
                    COmegaDamp(vals(i)) = NaN;
                    CDelta(vals(i)) = NaN;
                end
            end
            
            if omegaDN(end) < avgTrialVals
                omegaDN = omegaDN(1:end-1);
                omegDEdges = omegaDEdges(1:end-1);
                vals = find(COmegaDamp > omegaDEdges(end));
                for i=1:length(vals)
                    COmegaDamp(vals(i)) = NaN;
                    CDelta(vals(i)) = NaN;
                end
            end
            
            if deltaN(1) < avgTrialVals
                deltaN = deltaN(2:end);
                deltaEdges = deltaEdges(2:end);
                vals = find(CDelta < deltaEdges(1));
                for i=1:length(vals)
                    COmegaDamp(vals(i)) = NaN;
                    CDelta(vals(i)) = NaN;
                end
            end
            
            if deltaN(end) < avgTrialVals
                deltaN = deltaN(1:end-1);
                deltaEdges = deltaEdges(1:end-1);
                vals = find(CDelta > deltaEdges(end));
                for i=1:length(vals)
                    COmegaDamp(vals(i)) = NaN;
                    CDelta(vals(i)) = NaN;
                end
            end
        else
            outliers = 0;
        end
        COmegaDamp = rmmissing(COmegaDamp);
        CDelta = rmmissing(CDelta);
    end
    
    %Figure out error bars for C
    delCOmegaD = max(abs(mean(COmegaDamp) - COmegaDamp));
    delCDelta = max(abs(mean(CDelta) - CDelta));
    servoC = (mean(CDelta)*mean(COmegaDamp)*2*CSetup.mass)/(2*pi);
    delC = sqrt(delCDelta^2*((mean(COmegaDamp)*2*CSetup.mass)/(2*pi))+ delCOmegaD^2*((mean(CDelta)*2*CSetup.mass)/(2*pi))^2);
    disp(['Servo Damping Ratio: ', num2str(servoC), ' ',char(177), ' ', num2str(delC), ' (', num2str(delC/servoC*100),'% error)'])
end

    

When provided with the base file name, the file folder locations, and the number of trials in each folder, the program will automatically generate the full file path. As such, you can mess with the program on Lines 8-15 if you want to store files differently.

One common error with testing robust servo motors is the number of data points used. If not enough data points are found (<4), a larger leaver arm will need to be installed to enable to the arm to swing farther and log a better sinusoidal curve.

How this code removes outliers

This script attempts to eliminate outliers by looking at histogram bins for the data. This section of the code begins on Line 147. Essentially, it:

  • Uses histcounts to determine how many trials will be in each bin for δ\delta and ωd\omega_d separately.

  • The code keeps track of how many total trials were parsed in the previous lines, so it now calculates how many values for each parameter were contributed by a trial on average based on the length of the vectors.

  • Then, it checks each bin on either end of the data to see if the number of values is less than the average number contributed by a trial. If it is, it deletes that edge bin from both variables and moves on to checking the new edge bin. It does this until the edge bins for both variables contain more than a trial's worth of data points.

Running the Matlab Code

  1. Run servoCharacteristicCalculator.m

  2. Wait a while (it takes a bit, especially for a lot of trials)

Some Example Trials

A typical J trial.
A typical C trial

Last updated

Was this helpful?