<?xml version="1.0" encoding="UTF-8"?>
<rss xmlns:atom="http://www.w3.org/2005/Atom" version="2.0">
    <channel>
      <title>Home</title>
      <link>https://shaostassen.github.io/ShaoFastRobots</link>
      <description></description>
      <generator>Zola</generator>
      <language>en</language>
      <atom:link href="https://shaostassen.github.io/ShaoFastRobots/rss.xml" rel="self" type="application/rss+xml"/>
      <lastBuildDate>Mon, 23 Mar 2026 00:00:00 +0000</lastBuildDate>
      <item>
          <title>Lab 7: Kalman Filter</title>
          <pubDate>Mon, 23 Mar 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-7/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-7/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-7/">&lt;h2 id=&quot;drag-and-mass-estimations&quot;&gt;Drag and Mass Estimations&lt;&#x2F;h2&gt;
&lt;p&gt;Approximating the robot as a first-order system using Newton&#x27;s second law, factoring in linear drag $d$ and motor input $u$:&lt;&#x2F;p&gt;
&lt;p&gt;$$F = m\ddot{x} = -d\dot{x} + u$$&lt;&#x2F;p&gt;
&lt;p&gt;The dynamics in continuous state-space form ($\dot{x} = Ax + Bu$) with state vector $x = \begin{bmatrix} x \\ \dot{x} \end{bmatrix}$ are:&lt;&#x2F;p&gt;
&lt;p&gt;$$\begin{bmatrix} \dot{x} \\ \ddot{x} \end{bmatrix} = \begin{bmatrix} 0 &amp;amp; 1 \\ 0 &amp;amp; -\frac{d}{m} \end{bmatrix} \begin{bmatrix} x \\ \dot{x} \end{bmatrix} + \begin{bmatrix} 0 \\ \frac{1}{m} \end{bmatrix} u$$&lt;&#x2F;p&gt;
&lt;p&gt;I recorded three open-loop step responses at 150 PWM to extract parameters $d$ and $m$. Averaging these trajectories mitigated non-Gaussian Time-of-Flight (ToF) noise. Fitting an exponential decay to this consensus trajectory yielded a 70% rise time ($t_{0.7} = 1.05$ s) and steady-state velocity ($V_{ss} = 2.45$ m&#x2F;s).&lt;&#x2F;p&gt;
&lt;p&gt;Assuming a normalized unit step input ($u = 1$), the parameters are calculated as:&lt;&#x2F;p&gt;
&lt;p&gt;$$d = \frac{u_{ss}}{\dot{x}_{ss}} = \frac{1}{2.45} = 0.408$$&lt;&#x2F;p&gt;
&lt;p&gt;$$m = \frac{-d \cdot t_{0.7}}{\ln(0.3)} = \frac{-0.408 \cdot 1.05}{-1.204} = 0.356$$&lt;&#x2F;p&gt;
&lt;p&gt;Plugging these into our continuous $A$ and $B$ matrices yields:&lt;&#x2F;p&gt;
&lt;p&gt;$$A = \begin{bmatrix} 0 &amp;amp; 1 \\ 0 &amp;amp; -1.146 \end{bmatrix}, \quad B = \begin{bmatrix} 0 \\ 2.809 \end{bmatrix}$$&lt;&#x2F;p&gt;
&lt;p&gt;Measuring only distance, our observation matrix $C$ isolates the first state:&lt;&#x2F;p&gt;
&lt;p&gt;$$C = \begin{bmatrix} 1 &amp;amp; 0 \end{bmatrix}$$&lt;&#x2F;p&gt;
&lt;figure style=&quot;display: flex; justify-content: space-around; align-items: flex-start; gap: 10px; width: 100%;&quot;&gt;
&lt;div style=&quot;flex: 1; text-align: center;&quot;&gt;
&lt;img src=&quot;distance_time.jpg&quot; alt=&quot;d&quot; style=&quot;display:block; width:100%; max-width:400px; height:auto; margin: 0 auto;&quot;&gt;
&lt;figcaption style=&quot;margin-top: 5px;&quot;&gt;Average distance vs time for open loop step response&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;flex: 1; text-align: center;&quot;&gt;
&lt;img src=&quot;velocity.jpg&quot; alt=&quot;d&quot; style=&quot;display:block; width:100%; max-width:400px; height:auto; margin: 0 auto;&quot;&gt;
&lt;figcaption style=&quot;margin-top: 5px;&quot;&gt;Velocity and 70% rise time fit for open loop step response&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;flex: 1; text-align: center;&quot;&gt;
&lt;img src=&quot;pwm.jpg&quot; alt=&quot;d&quot; style=&quot;display:block; width:100%; max-width:400px; height:auto; margin: 0 auto;&quot;&gt;
&lt;figcaption style=&quot;margin-top: 5px;&quot;&gt;PWM graphs for open loop step response&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;Here is a video of one of the trajectories while I was collecting data for a step response:&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;74Vm-SvuMSU&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Data Collection Video&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;velocity2.jpg&quot; alt=&quot;c&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Velocity and 70% rise time fit for a better open loop step response&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;&lt;em&gt;Note: Subsequent trials with a closer braking distance yielded a slightly higher steady-state velocity, but my filter performed well with the initial dataset, so I proceeded with the originally calculated A and B matrices.&lt;&#x2F;em&gt;&lt;&#x2F;p&gt;
&lt;h2 id=&quot;kalman-python-simulation&quot;&gt;Kalman Python Simulation&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;system-timing-and-discretization&quot;&gt;System Timing and Discretization&lt;&#x2F;h3&gt;
&lt;p&gt;The continuous model must be discretized using the fast onboard prediction loop (50 Hz, $\Delta t = 0.0209$ s) rather than the slower ToF sensor rate (~10 Hz, $\Delta t = 0.0985$ s) to prevent artificially accelerating the physics.&lt;&#x2F;p&gt;
&lt;p&gt;Discretizing via the first-order Taylor expansion ($A_d = I + A\Delta t$ and $B_d = B\Delta t$):&lt;&#x2F;p&gt;
&lt;p&gt;$$A_d = \begin{bmatrix} 1 &amp;amp; 0 \\ 0 &amp;amp; 1 \end{bmatrix} + \begin{bmatrix} 0 &amp;amp; 1 \\ 0 &amp;amp; -1.146 \end{bmatrix}(0.0209) = \begin{bmatrix} 1 &amp;amp; 0.0209 \\ 0 &amp;amp; 0.976 \end{bmatrix}$$&lt;&#x2F;p&gt;
&lt;p&gt;$$B_d = \begin{bmatrix} 0 \\ 2.809 \end{bmatrix}(0.0209) = \begin{bmatrix} 0 \\ 0.0587 \end{bmatrix}$$&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;import&lt;&#x2F;span&gt;&lt;span&gt; numpy&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; as&lt;&#x2F;span&gt;&lt;span&gt; np&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# Discretized Matrices&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;Ad&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; np.array([[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0209&lt;&#x2F;span&gt;&lt;span&gt;], [&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.976&lt;&#x2F;span&gt;&lt;span&gt;]])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;Bd&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; np.array([[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.0&lt;&#x2F;span&gt;&lt;span&gt;], [&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.0587&lt;&#x2F;span&gt;&lt;span&gt;]])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;C&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; np.array([[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;]])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# Noise Covariances&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;sig_u&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; np.array([[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;10.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;**&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;], [&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 10.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;**&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;]]) &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;sig_z&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; np.array([[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;20.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;**&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;]])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# Kalman Filter Simulation Function&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;def&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; kalman_filter&lt;&#x2F;span&gt;&lt;span&gt;(mu, sigma, u, y_meas, has_new_data):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # Predict Step&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    mu_p&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; Ad.dot(mu)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; Bd.dot(u)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sigma_p&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; Ad.dot(sigma).dot(Ad.T)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; sig_u&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; has_new_data:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        # Update Step&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        y_m&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; y_meas&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; C.dot(mu_p)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        S&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; C.dot(sigma_p).dot(C.T)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; sig_z&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        K&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; sigma_p.dot(C.T).dot(np.linalg.inv(S))&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        mu&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; mu_p&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; K.dot(y_m)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        sigma&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; (np.eye(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; K.dot(C)).dot(sigma_p)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    else&lt;&#x2F;span&gt;&lt;span&gt;:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        mu&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; mu_p&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        sigma&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; sigma_p&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    return&lt;&#x2F;span&gt;&lt;span&gt; mu, sigma&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;simulation-debugging&quot;&gt;Simulation Debugging&lt;&#x2F;h3&gt;
&lt;figure&gt;
&lt;img src=&quot;first_attempt.jpg&quot; alt=&quot;Unit Mismatch Graph&quot; style=&quot;display:block; width:100%; max-width:600px; margin: 0 auto;&quot;&gt;
&lt;figcaption&gt;Simulation Attempt 1: Unit Mismatch resulting in apparent zero velocity.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;&lt;strong&gt;1. Unit Mismatch:&lt;&#x2F;strong&gt; The matrices initially predicted velocity in m&#x2F;s, while raw data was plotted in mm&#x2F;s, causing the accurate -3.1 m&#x2F;s prediction to appear as a flat line on a -3000 mm&#x2F;s scale. Recalculating matrices in millimeters fixed this.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;second_attempt.jpg&quot; alt=&quot;Delta t Mismatch Graph&quot; style=&quot;display:block; width:100%; max-width:600px; margin: 0 auto;&quot;&gt;
&lt;figcaption&gt;Simulation Attempt 2: Discretization timing mismatch causing extreme acceleration.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;&lt;strong&gt;2. Discretization Mismatch:&lt;&#x2F;strong&gt; The simulated velocity reached steady-state too quickly (0.25s vs 1.06s) because $A_d$ and $B_d$ were mistakenly discretized using the 0.1s ToF rate instead of the simulation grid&#x27;s interval. Using the correct $\Delta t = 0.0209$ s resolved the 5x artificial acceleration.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;sensor-noise-characterization-and-final-tuning&quot;&gt;Sensor Noise Characterization and Final Tuning&lt;&#x2F;h3&gt;
&lt;p&gt;Stationary tests revealed distance-dependent noise: $\sigma_{start} \approx 19.2$ mm (at 3800 mm) and $\sigma_{target} \approx 1.2$ mm (at 430 mm).&lt;&#x2F;p&gt;
&lt;figure style=&quot;display: flex; justify-content: space-around; align-items: flex-start; gap: 10px; width: 100%;&quot;&gt;
&lt;div style=&quot;flex: 1; text-align: center;&quot;&gt;
&lt;img src=&quot;station_3800mm.jpg&quot; alt=&quot;Stationary Noise at Far Distance&quot; style=&quot;display:block; width:100%; max-width:400px; height:auto; margin: 0 auto;&quot;&gt;
&lt;figcaption style=&quot;margin-top: 5px;&quot;&gt;Stationary Noise at Start (~3860mm): $sigma = 19.244$ mm&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;flex: 1; text-align: center;&quot;&gt;
&lt;img src=&quot;tof_noise_304.jpg&quot; alt=&quot;Stationary Noise at Close Distance&quot; style=&quot;display:block; width:100%; max-width:400px; height:auto; margin: 0 auto;&quot;&gt;
&lt;figcaption style=&quot;margin-top: 5px;&quot;&gt;Stationary Noise near Target (~430mm): $sigma = 1.223$ mm&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;To prevent violent derivative kick at high speeds, I tuned the measurement covariance ($\Sigma_z$) for the worst-case scenario.&lt;&#x2F;p&gt;
&lt;p&gt;$$
\Sigma_u = \begin{bmatrix} 100.0 &amp;amp; 0 \\ 0 &amp;amp; 100.0 \end{bmatrix}, \quad \Sigma_z = \begin{bmatrix} 400.0 \end{bmatrix}
$$&lt;&#x2F;p&gt;
&lt;p&gt;In the Kalman Gain equation, setting $\Sigma_z = 400.0 \gg \Sigma_u = 100.0$ drastically shrinks the gain $K$. Consequently, the update equation ($\mu = \mu_p + K(y - C\mu_p)$) minimizes the impact of noisy sensor residuals. The system heavily trusts the physical prediction ($\mu_p$), allowing the velocity estimate to slice cleanly through the initial noise cloud.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;third_attempt.jpg&quot; alt=&quot;Properly Tuned KF Graph&quot; style=&quot;display:block; width:100%; max-width:600px; margin: 0 auto;&quot;&gt;
&lt;figcaption&gt;Simulation Attempt 3: Fully tuned Kalman Filter accurately tracking distance and filtering velocity.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h2 id=&quot;onboard-robot-kalman-integration&quot;&gt;Onboard Robot Kalman Integration&lt;&#x2F;h2&gt;
&lt;p&gt;The &lt;code&gt;BasicLinearAlgebra&lt;&#x2F;code&gt; library was used to port the matrices directly to the Artemis board. The control loop was decoupled from the sensor, executing the prediction step on a strict 50 Hz timer and updating only when the &lt;code&gt;has_new_data&lt;&#x2F;code&gt; flag triggered.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;#include&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;lt;BasicLinearAlgebra.h&amp;gt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;using namespace&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; BLA&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; Ad &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0209&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.976&lt;&#x2F;span&gt;&lt;span&gt;}; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; Bd &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0587&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; C  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; sig_u &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;100.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 100.0&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; sig_z &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;400.0&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; mu &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; sigma &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;10.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 10.0&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; update_kalman&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;bool&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; has_new_data&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; float&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; measured_distance&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; float&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; current_pwm&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; u &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {current_pwm &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 150.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;};&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt; &#x2F;&#x2F; Scale input to unit step&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; mu_p &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; Ad &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; mu &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; Bd &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; u;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; sigma_p &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; Ad &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; sigma &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;* ~&lt;&#x2F;span&gt;&lt;span&gt;Ad &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; sig_u;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (has_new_data) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; y &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; {measured_distance};&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; S &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; C &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; sigma_p &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;* ~&lt;&#x2F;span&gt;&lt;span&gt;C &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; sig_z;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; S_inv &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; S; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        Invert&lt;&#x2F;span&gt;&lt;span&gt;(S_inv);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        BLA&lt;&#x2F;span&gt;&lt;span&gt;::Matrix&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; K &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sigma_p &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;* ~&lt;&#x2F;span&gt;&lt;span&gt;C &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; S_inv;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        mu &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; mu_p &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; K &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; (y &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; C &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; mu_p);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        sigma &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;Eye&lt;&#x2F;span&gt;&lt;span&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span&gt;&amp;gt;()&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; K &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; C)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; sigma_p;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; else&lt;&#x2F;span&gt;&lt;span&gt; {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        mu &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; mu_p; sigma &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sigma_p;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; executeControl&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    uint32_t&lt;&#x2F;span&gt;&lt;span&gt; now &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (now &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; last_fast_loop_time &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 20000&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt; &#x2F;&#x2F; 50Hz Fast Loop&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        last_fast_loop_time &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; now;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        update_kalman&lt;&#x2F;span&gt;&lt;span&gt;(new_tof_data, dist_k, current_applied_pwm);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        new_tof_data &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; false&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        float&lt;&#x2F;span&gt;&lt;span&gt; kf_distance &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; mu&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        float&lt;&#x2F;span&gt;&lt;span&gt; raw_control_effort &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; computePID&lt;&#x2F;span&gt;&lt;span&gt;(linear_pid_setpoint, kf_distance);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        int&lt;&#x2F;span&gt;&lt;span&gt; actual_pwm &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; applyMotorSpeed&lt;&#x2F;span&gt;&lt;span&gt;(raw_control_effort);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        current_applied_pwm &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; actual_pwm; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;pid-tuning-and-derivative-kick&quot;&gt;PID Tuning and Derivative Kick&lt;&#x2F;h3&gt;
&lt;figure&gt;
&lt;img src=&quot;high_kd.jpg&quot; alt=&quot;High Kd Oscillation&quot; style=&quot;display:block; width:100%; max-width:600px; margin: 0 auto;&quot;&gt;
&lt;figcaption&gt;Phase 1: Extreme oscillation caused by Lab 5 derivative gains applied to the fast loop.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;&lt;strong&gt;Phase 1: Timing Mismatch:&lt;&#x2F;strong&gt; Applying Lab 5 PD gains ($K_p = 0.025$, $K_d = 20000$) to the 50 Hz loop caused violent oscillations. Because the new $\Delta t$ (0.020s) was five times smaller than the old ToF interval (0.098s), the discrete derivative ($K_d \frac{de}{dt}$) effectively multiplied the derivative kick by 5.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;no_kd_low_kp.jpg&quot; alt=&quot;Zero Kd Coasting&quot; style=&quot;display:block; width:100%; max-width:600px; margin: 0 auto;&quot;&gt;
&lt;figcaption&gt;Phase 2: Proportional-only control resulting in a slow approach and failure to stop.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;&lt;strong&gt;Phase 2: Coasting Baseline:&lt;&#x2F;strong&gt; Disabling the derivative term ($K_d = 0$) and using $K_p = 0.015$ eliminated oscillations, but without a derivative &quot;brake,&quot; the robot coasted through the 304 mm target and crashed.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;finetuned.jpg&quot; alt=&quot;Tuned KF Response&quot; style=&quot;display:block; width:100%; max-width:600px; margin: 0 auto;&quot;&gt;
&lt;figcaption&gt;Phase 3: Final tuned response utilizing the Kalman Filter for smooth, aggressive braking.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;&lt;strong&gt;Phase 3: Kalman Velocity Control:&lt;&#x2F;strong&gt; To safely restore braking power, I substituted the Kalman Filter&#x27;s smoothed velocity state ($\mu_1$) for the noisy discrete derivative calculation:&lt;&#x2F;p&gt;
&lt;p&gt;$$u(t) = K_p(x_{target} - \mu_0) - K_d(\mu_1)$$&lt;&#x2F;p&gt;
&lt;p&gt;This eliminated derivative chatter entirely. Approaching the 300 mm mark, $\mu_1$ applies a clean electronic braking force for a perfectly controlled stop.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;HNZxEkrY4M4&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Linear PID Test with Tuned Kalman Filter&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;final-remark&quot;&gt;Final Remark&lt;&#x2F;h3&gt;
&lt;p&gt;While implementation was challenging, the resulting performance was highly satisfying. I achieved rapid initial acceleration (starting at max 255 PWM and decreasing to 100 PWM within the first second), covering significant distance quickly before the filter seamlessly executed the braking maneuver.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h2&gt;
&lt;p&gt;I referred to Jack Long and Aidan McNay&#x27;s pages for graphing techniques and Kalman Filter C++ architectures. I collaborated with Ananya Jajodia on collecting step response data, and utilized ChatGPT to assist with data visualization and report formatting.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 6: Orientation Control</title>
          <pubDate>Tue, 17 Mar 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-6/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-6/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-6/">&lt;h2 id=&quot;objective&quot;&gt;Objective&lt;&#x2F;h2&gt;
&lt;p&gt;The purpose of this lab is to implement a robust PID controller to manage the orientation (yaw) of the robot. This involves utilizing the IMU to perform in-place rotation using differential drive, while mitigating real-world sensor issues like gyroscope drift and derivative kick.&lt;&#x2F;p&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;prelab-bluetooth-architecture-and-dynamic-setpoints&quot;&gt;Prelab: Bluetooth Architecture and Dynamic Setpoints&lt;&#x2F;h2&gt;
&lt;p&gt;To allow rapid tuning and mid-run setpoint changes, the Bluetooth handling was designed to be completely non-blocking. This is exactly how I transferred data in Lab 5 using commands. Instead of trapping the robot in a &lt;code&gt;while&lt;&#x2F;code&gt; loop during a turn, the main &lt;code&gt;loop()&lt;&#x2F;code&gt; continuously cycles through telemetry, sensor reading, and motor updating.&lt;&#x2F;p&gt;
&lt;p&gt;This architecture allowed me to implement a dedicated &lt;code&gt;UPDATE_YAW_SETPOINT&lt;&#x2F;code&gt; BLE command.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; UPDATE_YAW_SETPOINT: {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    float&lt;&#x2F;span&gt;&lt;span&gt; new_yaw;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(new_yaw);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    rotational_setpoint &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; new_yaw;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; ... [telemetry logging]&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;This satisfies the requirement to change the setpoint dynamically without halting the system. By passing new floats over Bluetooth, I can command the robot to snap to 90 degrees, and before it even finishes the turn, update the setpoint to -45 degrees seamlessly.&lt;&#x2F;p&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;pid-input-signal-and-gyroscope-bias&quot;&gt;PID Input Signal and Gyroscope Bias&lt;&#x2F;h2&gt;
&lt;p&gt;Initially, standard digital integration of the raw gyroscope data (&lt;code&gt;gyrZ()&lt;&#x2F;code&gt;) was tested to estimate orientation. However, a stationary test revealed significant hardware bias and a ton of sensor noise (setting up for the Kalman filter), drifting at approximately -0.24 degrees per second.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;yaw_state.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Yaw value of a stationary IMU sitting flat on the table&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;yaw_drift.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Drift in yaw value of a stationary IMU over time&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;yaw_360.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Yaw value of the IMU performing a 360-degree turn&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;As you can see from the figures above, the IMU works fairly well measuring yaw when rotating slowly, but this is not the case if the car is spinning at full speed, which incurs a lot of drift. This called the DMP to the rescue.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;the-digital-motion-processor-dmp-solution&quot;&gt;The Digital Motion Processor (DMP) Solution&lt;&#x2F;h3&gt;
&lt;p&gt;To eliminate this bias, I bypassed manual integration and enabled the ICM-20948&#x27;s onboard Digital Motion Processor (DMP). By configuring the DMP to output the 6-axis Game Rotation Vector (Quat6) at maximum speed (55Hz), the hardware&#x27;s sensor fusion algorithm automatically corrects for drift in the background.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Keep reading until the FIFO queue is completely empty&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    while&lt;&#x2F;span&gt;&lt;span&gt; (myICM.status&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; ==&lt;&#x2F;span&gt;&lt;span&gt; ICM_20948_Stat_FIFOMoreDataAvail) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;readDMPdataFromFIFO&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt;data);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; ... [Quaternion to Euler conversion] ...&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    yaw_g_state &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; raw_yaw &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; yaw_offset;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt; &#x2F;&#x2F; Zero out relative to start heading&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;To prevent the DMP&#x27;s internal FIFO queue from overflowing and crashing the sensor, a &lt;code&gt;while&lt;&#x2F;code&gt; loop was used to completely drain the queue, ensuring the PID loop always acts on the freshest, completely drift-free quaternion data.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;proportional-only-tune&quot;&gt;Proportional Only Tune&lt;&#x2F;h2&gt;
&lt;p&gt;Initially, I started Kp at 0.9. Because the orientation ranges from -180 to 180 degrees, I mapped this against the PWM range using the deadband limit of 90 to 255 (a range of 165) that I learned from Lab 4. I then tuned the P value by increasing it slowly. Here is the result of this P-only controller targeting 90 degrees.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;MvP56cXlcOk&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Initial P controller&lt;&#x2F;figcaption&gt;
&lt;h2 id=&quot;the-derivative-term-and-anti-kick&quot;&gt;The Derivative Term and Anti-Kick&lt;&#x2F;h2&gt;
&lt;p&gt;It does not make sense to take the derivative of a signal that is the integral of another signal. Taking the mathematical derivative of the error &lt;code&gt;(error - prev_error) &#x2F; dt&lt;&#x2F;code&gt; just undoes the integration while amplifying digital noise. Furthermore, if the setpoint is suddenly changed (e.g., commanding a turn from 0° to 90° mid-run), the error instantly spikes. Taking the derivative of this sudden step-change results in a near-infinite spike in the D-term, causing the motors to jolt violently.&lt;&#x2F;p&gt;
&lt;p&gt;Because the derivative of a constant setpoint is zero, the derivative of the error is mathematically equal to the negative of the actual rate of change. I bypassed the standard math and fed the raw gyroscope rate (&lt;code&gt;-myICM.gyrZ()&lt;&#x2F;code&gt;) directly into the D-term.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; ANTI-DERIVATIVE KICK: Use raw gyro rate instead of (error - prev_error)&#x2F;dt&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    float&lt;&#x2F;span&gt;&lt;span&gt; derivative &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;= -&lt;&#x2F;span&gt;&lt;span&gt;gyro_rate; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    float&lt;&#x2F;span&gt;&lt;span&gt; D &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; Kd &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; derivative;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;NCYYelEjF5c&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;With a setpoint of 90 degrees, the car reacts to constant external turning&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;external.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Yaw vs. time at 90 degrees with external disturbance&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h2 id=&quot;orientation-control-and-tuning&quot;&gt;Orientation Control and Tuning&lt;&#x2F;h2&gt;
&lt;p&gt;Control relies on differential drive, passing &lt;code&gt;control_effort&lt;&#x2F;code&gt; to the left motor and &lt;code&gt;-control_effort&lt;&#x2F;code&gt; to the right motor using the calibrated motor functions from Lab 5. During initial testing, I accidentally created a positive feedback loop because turning the robot physically right yielded a negative IMU angle, causing the error to grow rather than shrink. Flipping the motor command signs instantly fixed this.&lt;&#x2F;p&gt;
&lt;p&gt;Here is an example of the error, where before the derivative term could brake the bot, its momentum carried it past the setpoint, resulting in constant spinning.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;aPiQhUuWHdg&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt; Positive feedback resulting in endless spinning &lt;&#x2F;figcaption&gt;
&lt;p&gt;During tuning, the integral term (&lt;strong&gt;Ki&lt;&#x2F;strong&gt;) was kept at 0 to avoid integrator wind-up at first, as steady-state error is minimal for free-spinning wheels on a smooth floor. I did implement wind-up protection (&lt;code&gt;constrain(integral_sum, -50.0, 50.0);&lt;&#x2F;code&gt;), and later, when I noticed persistent small errors between my PD controller and the setpoints, I added the integral term.&lt;&#x2F;p&gt;
&lt;p&gt;I increased the proportional gain (&lt;strong&gt;Kp&lt;&#x2F;strong&gt;) until the robot snapped to the target quickly, then applied the derivative gain (&lt;strong&gt;Kd&lt;&#x2F;strong&gt;) to dampen the resulting oscillations.&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;&lt;strong&gt;Final Kp:&lt;&#x2F;strong&gt; &lt;code&gt;10.0&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Final Kd:&lt;&#x2F;strong&gt; &lt;code&gt;0.5&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Final Ki:&lt;&#x2F;strong&gt; &lt;code&gt;0.5&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;h3 id=&quot;system-response-and-results&quot;&gt;System Response and Results&lt;&#x2F;h3&gt;
&lt;p&gt;Below are the results of the tuned PID controller handling consecutive setpoints (0 -&amp;gt; 90 -&amp;gt; -90 -&amp;gt; 45 degrees) where I updated the yaw setpoint every 5 seconds. I tested this on two different surfaces: hard floor vs. carpet.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;xDcn3u4P5s4&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Floor setting&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;without_i.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Yaw vs. time with setpoint updates on floor&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;wg8QhRoUuI0&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Carpet setting&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;with_i.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Yaw vs. time with setpoint updates on carpet&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h2 id=&quot;discussion&quot;&gt;Discussion&lt;&#x2F;h2&gt;
&lt;p&gt;When I was tuning the integral terms of the PID controller on the carpet, I observed the situation below:&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;zwCbHPWFi0w&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;High Pitch Sound on Carpet with No Motion&lt;&#x2F;figcaption&gt;
&lt;p&gt;After investigation, I realized this meant the battery was dying and simply needed to be charged.&lt;&#x2F;p&gt;
&lt;p&gt;According to the ICM-20948 datasheet, the gyroscope has a programmable full-scale range (±250, ±500, ±1000, or ±2000 dps). During a rapid pivot, my robot easily spins faster than 250 dps. If left on the default ±250 dps setting, a fast turn would saturate the sensor, capping the output and causing my derivative &quot;brake&quot; to underestimate the speed. Using the ±2000 dps range provides ample headroom to capture the maximum rotational velocity.&lt;&#x2F;p&gt;
&lt;p&gt;Because I bypassed standard error derivation and used the raw gyrZ() reading for Kd, any high-frequency mechanical vibration or electrical noise gets directly multiplied by Kd, causing motor jitter. I relied on the ICM-20948&#x27;s built-in Digital Low-Pass Filter (DLPF) to clean up the raw data before feeding it into the PID math.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h2&gt;
&lt;p&gt;I referenced Lucca Correia&#x27;s site for debugging and testing help. ChatGPT was used to help with some website formatting.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 5: Linear PID Control and Linear Interpolation</title>
          <pubDate>Sun, 15 Mar 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-5/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-5/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-5/">&lt;h2 id=&quot;objective&quot;&gt;Objective&lt;&#x2F;h2&gt;
&lt;p&gt;The goal is to implement a robust linear PID controller to drive the robot quickly toward a wall, stopping exactly 304mm (1 foot) away. Linear extrapolation is used to decouple the high-frequency PID control loop from the slower Time-of-Flight (ToF) sensor data rate.&lt;&#x2F;p&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;prelab-bluetooth-architecture-and-debugging&quot;&gt;Prelab: Bluetooth Architecture and Debugging&lt;&#x2F;h2&gt;
&lt;p&gt;To prevent &lt;code&gt;Serial.print&lt;&#x2F;code&gt; or Bluetooth delays from slowing down the PID loop, debugging data is stored locally in arrays during the run.&lt;&#x2F;p&gt;
&lt;p&gt;The test sequence is controlled via Python over BLE. &lt;code&gt;START_LINEAR_PID_DATA&lt;&#x2F;code&gt; triggers the control loop with the 304mm setpoint. &lt;code&gt;SET_PID&lt;&#x2F;code&gt; allows real-time tuning of &lt;strong&gt;Kp&lt;&#x2F;strong&gt;, &lt;strong&gt;Ki&lt;&#x2F;strong&gt;, and &lt;strong&gt;Kd&lt;&#x2F;strong&gt; without recompiling. Once finished, &lt;code&gt;STOP_LINEAR_PID_DATA&lt;&#x2F;code&gt; halts the motors and transmits the data to Python for visualization. This is almost exactly like how I have been transfer data in previous lab using commands.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;debug.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Here is an example of ToF data being sent over the network for debugging.&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;position-control-implementation&quot;&gt;Position Control Implementation&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;tof-sensor-configuration-and-testing-challenges&quot;&gt;ToF Sensor Configuration and Testing Challenges&lt;&#x2F;h3&gt;
&lt;p&gt;Initial testing was frustrating. I used the Long &lt;code&gt;distanceMode&lt;&#x2F;code&gt; to potentially start up to 4 meters away, but the ToF sensor continuously failed to read past 1.8 meters on the ground. After hours of debugging and swapping between two cars, I found the culprits: both cars&#x27; ToF sensors pointed slightly downward, and the carpet strongly scattered the IR waves.&lt;&#x2F;p&gt;
&lt;p&gt;Moving my tests to the hallway instantly fixed the reliability issues. While this provided clean data from 3 meters out, it reduced the sampling rate to roughly 20Hz.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;motor-deadband-and-scaling-calibration&quot;&gt;Motor Deadband and Scaling Calibration&lt;&#x2F;h3&gt;
&lt;p&gt;To allow micro-adjustments near the target, &lt;code&gt;driveCalibrated()&lt;&#x2F;code&gt; handles the motor deadband.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; driveCalibrated&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; left_speed&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; float&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; right_speed&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;motors_enabled)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Constrain before scaling to prevent full-throttle drift&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    left_speed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(left_speed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;255.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255.0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    right_speed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(right_speed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;255.0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255.0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    left_speed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*=&lt;&#x2F;span&gt;&lt;span&gt; left_motor_scaling;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    right_speed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*=&lt;&#x2F;span&gt;&lt;span&gt; right_motor_scaling;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;fabs&lt;&#x2F;span&gt;&lt;span&gt;(left_speed)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.1&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        int&lt;&#x2F;span&gt;&lt;span&gt; pwm_l &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; map&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;fabs&lt;&#x2F;span&gt;&lt;span&gt;(left_speed),&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;, min_pwm_left,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        pwm_l &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(pwm_l, min_pwm_left,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; ... (Directional logic and right motor logic follows)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;The PID output maps an effort of &quot;1&quot; to the minimum PWM needed to overcome static friction (~40 PWM). The raw input is constrained &lt;em&gt;before&lt;&#x2F;em&gt; scaling, ensuring straight driving even at maximum PID output.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;proportional-p-control-tuning&quot;&gt;Proportional (P) Control Tuning&lt;&#x2F;h3&gt;
&lt;p&gt;Starting 3000mm away with a 304mm setpoint creates a massive initial error (~2696mm).  &lt;strong&gt;Kp&lt;&#x2F;strong&gt; of 1 would dangerously saturate the motors. A viable gain range to keep commands within 0-255 bounds is between &lt;strong&gt;Kp = 0.005&lt;&#x2F;strong&gt; (conservative) and &lt;strong&gt;0.009&lt;&#x2F;strong&gt; (aggressive).&lt;&#x2F;p&gt;
&lt;p&gt;My initial tests were from 1800mm due to the early sensor issues.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;vyQKNND2o0w&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;1800mm P Test&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;initP.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;P-only PID control, ToF Distance vs. Time &lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;While P-control was fairly accurate, higher speeds caused overshoot. Adding a Derivative (&lt;strong&gt;Kd&lt;&#x2F;strong&gt;) term acted as a brake, allowing a higher P-term.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;g93l-az-CnU&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;1800mm PD Test&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;tuneD.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;PD control, ToF Distance vs. Time &lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;My final tuned gains were &lt;strong&gt;Kp = 0.0025&lt;&#x2F;strong&gt;, &lt;strong&gt;Kd = 20000.0&lt;&#x2F;strong&gt;, and &lt;strong&gt;Ki = 0&lt;&#x2F;strong&gt;. I omitted the I-term since there was no observable steady-state error.&lt;&#x2F;p&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;linear-extrapolation&quot;&gt;Linear Extrapolation&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;the-sampling-rate-problem&quot;&gt;The Sampling Rate Problem&lt;&#x2F;h3&gt;
&lt;p&gt;The ToF sensor runs at 18-20Hz, but the main PID loop executes hundreds of times per second. Without extrapolation, using stale distance data for 50ms causes jerky movements and discrete derivative steps.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;implementation&quot;&gt;Implementation&lt;&#x2F;h3&gt;
&lt;p&gt;To decouple these rates, &lt;code&gt;readToF()&lt;&#x2F;code&gt; calculates the PID effort every loop cycle. If no new data is ready, it estimates the current distance using velocity from the last two readings:&lt;&#x2F;p&gt;
&lt;p&gt;$$d_{est} = d_{last} + (v \cdot \Delta t)$$&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    float&lt;&#x2F;span&gt;&lt;span&gt; estimated_distance &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; last_known_dist; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;new_data_available &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;amp;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt; prev_known_time &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        float&lt;&#x2F;span&gt;&lt;span&gt; dt_history &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (last_known_time &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; prev_known_time)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1000000.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        if&lt;&#x2F;span&gt;&lt;span&gt; (dt_history &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            float&lt;&#x2F;span&gt;&lt;span&gt; velocity &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (last_known_dist &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; prev_known_dist)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; dt_history; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            float&lt;&#x2F;span&gt;&lt;span&gt; time_since_last &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (current_time &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; last_known_time)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1000000.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            estimated_distance &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; last_known_dist &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; (velocity &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; time_since_last);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Execute PID immediately using the estimated distance&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (run_linear_pid) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        float&lt;&#x2F;span&gt;&lt;span&gt; control_effort &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; computePID&lt;&#x2F;span&gt;&lt;span&gt;(linear_pid_setpoint, estimated_distance);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;        driveCalibrated&lt;&#x2F;span&gt;&lt;span&gt;(control_effort, control_effort);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;extrapolated-results&quot;&gt;Extrapolated Results&lt;&#x2F;h3&gt;
&lt;p&gt;With extrapolation, the PID loop runs continuously at over 150Hz. The robot smoothly ramps down its motor speed between sensor flashes, allowing higher top speeds safely. The plots show true sensor readings at ~20Hz alongside high-frequency motor command adjustments. I recorded three trials of this extrapolated controller.&lt;&#x2F;p&gt;
&lt;div style=&quot;display: flex; flex-wrap: wrap; align-items: center; justify-content: space-between; margin-bottom: 40px;&quot;&gt;
&lt;div style=&quot;flex: 0 0 48%; min-width: 300px;&quot;&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;dOP3MGeF_IE&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Trial 1 Video&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;flex: 0 0 48%; min-width: 300px;&quot;&gt;
&lt;figure style=&quot;margin: 0;&quot;&gt;
&lt;img src=&quot;trial1.jpg&quot; alt=&quot;Trial 1 Plot&quot; style=&quot;display:block; width:100%;&quot;&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Trial 1: ToF Distance vs. Time&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;display: flex; flex-wrap: wrap; align-items: center; justify-content: space-between; margin-bottom: 40px;&quot;&gt;
&lt;div style=&quot;flex: 0 0 48%; min-width: 300px;&quot;&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;33lLNpuxZKE&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Trial 2 Video&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;flex: 0 0 48%; min-width: 300px;&quot;&gt;
&lt;figure style=&quot;margin: 0;&quot;&gt;
&lt;img src=&quot;trial2.jpg&quot; alt=&quot;Trial 2 Plot&quot; style=&quot;display:block; width:100%;&quot;&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Trial 2: ToF Distance vs. Time&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;display: flex; flex-wrap: wrap; align-items: center; justify-content: space-between; margin-bottom: 40px;&quot;&gt;
&lt;div style=&quot;flex: 0 0 48%; min-width: 300px;&quot;&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;v3NTideadpo&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Trial 3 Video&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;flex: 0 0 48%; min-width: 300px;&quot;&gt;
&lt;figure style=&quot;margin: 0;&quot;&gt;
&lt;img src=&quot;trial3.jpg&quot; alt=&quot;Trial 3 Plot&quot; style=&quot;display:block; width:100%;&quot;&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Trial 3: ToF Distance vs. Time&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;p&gt;Motor effort is the negative of PWM, due to some sign in calculation that&#x27;s hard to fix. The max speed I acheieve with my linear PID while successful is approximately &lt;strong&gt;1 m&#x2F;s&lt;&#x2F;strong&gt;, this could be find via slope from above graphs.
Finally, I shoved the car while the linear PID was active to test how well it adapted to changing states and external disturbances.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;sTJlFlL0Tps&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption style=&quot;text-align: center; font-style: italic;&quot;&gt;Disturbance Test Video&lt;&#x2F;figcaption&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;discussion-and-additional-implementations&quot;&gt;Discussion and Additional Implementations&lt;&#x2F;h2&gt;
&lt;p&gt;To ensure the robot drove straight even when the PID demanded maximum effort, I implemented &lt;strong&gt;pre-constraining&lt;&#x2F;strong&gt; on the PID output before applying the differential &lt;strong&gt;motor scaling factors&lt;&#x2F;strong&gt;. I also kept the Bluetooth &lt;code&gt;read_data()&lt;&#x2F;code&gt; and &lt;code&gt;write_data()&lt;&#x2F;code&gt; handlers entirely &lt;strong&gt;non-blocking&lt;&#x2F;strong&gt; so the main control loop could maintain its high-frequency execution.&lt;&#x2F;p&gt;
&lt;hr &#x2F;&gt;
&lt;h2 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h2&gt;
&lt;p&gt;I collaborated on this project with Ananya Jajodia on troubleshooting my car. I also referenced Aiden Derocher&#x27;s site for debugging and testing help. ChatGPT was used to help with some website formatting.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 4: Motor Drivers and Open Loop Control</title>
          <pubDate>Mon, 02 Mar 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/Lab 4/index-2/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/Lab 4/index-2/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/Lab 4/index-2/">&lt;h2 id=&quot;prelab&quot;&gt;Prelab&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;wire-schematic&quot;&gt;Wire Schematic&lt;&#x2F;h3&gt;
&lt;p&gt;To control the motors, I utilized the PWM-capable pins on the Artemis Nano. I assigned pins 15 and 14 for the Left Motor (forward and backward, respectively) and 2 and 3 for the Right Motor. These pins were chosen to keep the wiring organized and relatively localized on the board, leaving the other side available for future sensor expansion.&lt;&#x2F;p&gt;
&lt;p&gt;To ensure the motors receive enough current without overheating the motor drivers, the inputs and outputs of each dual motor driver were parallel-coupled. This effectively combines the two channels of a single IC, doubling the average current capacity sent to each DC motor.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;wire_diagram.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;System Circuit Schematic&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h2 id=&quot;lab-tasks&quot;&gt;Lab Tasks&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;soldering-the-circuit&quot;&gt;Soldering the Circuit&lt;&#x2F;h3&gt;
&lt;p&gt;Below is an image of the finished, soldered physical circuit. (Note: The circuit had not been mounted into the chassis before my initial PWM tests; I just forgot to photograph it prior to this step!)&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;physical_circuit.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Finished System Circuit&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h3 id=&quot;power-supply-and-oscilloscope-hookup&quot;&gt;Power Supply and Oscilloscope Hookup&lt;&#x2F;h3&gt;
&lt;p&gt;Before integrating the drivers into the car, I tested the PWM outputs using an oscilloscope and an external power supply. The power supply was set to 3.7V with a conservative current limit to simulate the 850mAh Li-Ion battery, which prevents any real damage in the event of a short circuit or a bad soldering job.&lt;&#x2F;p&gt;
&lt;p&gt;To verify the PWM generation, I used the following basic code to send a duty cycle of approximately 23% (60&#x2F;255) to pin 15, representing the forward direction:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;#define&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; MOTOR_INL1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 15&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;#define&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; MOTOR_INL2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 14&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; setup&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  pinMode&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, OUTPUT);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  pinMode&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, OUTPUT);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; loop&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 60&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;MVw43_S0BW8&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Left Motor Driver PWM Test&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;oscilloscope1.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Oscilloscope capturing the PWM signal&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;DooZhPy4oLc&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Regulated Left Motor Driver PWM Test&lt;&#x2F;figcaption&gt;
&lt;figure&gt;
&lt;img src=&quot;oscilloscope2.PNG&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Oscilloscope capturing the PWM signal&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;LsvBeuKERr4&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Regulated Right Motor Driver PWM Test&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;motor-testing&quot;&gt;Motor Testing&lt;&#x2F;h3&gt;
&lt;p&gt;After validating the signal, I dismantled the Force1 RC car. I decided not to remove the stock PCB, thinking the flat surface would be useful for mounting my components (although I ultimately didn&#x27;t take much advantage of it for this lab). I then cut the motor leads and wired up the left motor driver first, keeping the chassis elevated so the wheels could spin freely.&lt;&#x2F;p&gt;
&lt;p&gt;During this phase, I ran into a frustrating bug while testing the second motor driver. I wrote the exact same PWM code to verify the motor functioned correctly, but it refused to spin. After extensive troubleshooting, I finally connected the &lt;code&gt;VIN&lt;&#x2F;code&gt; and &lt;code&gt;GND&lt;&#x2F;code&gt; leads of both motor drivers together into the power supply, and it worked perfectly—even though I was only actively controlling one driver.&lt;&#x2F;p&gt;
&lt;p&gt;This is a classic grounding issue. In complex or high-power robotics—like the 3lb autonomous combat robots built for competition—ensuring a shared, common ground between your logic controller (the Artemis) and your motor drivers is critical. Without a shared ground reference, the PWM signal from the Artemis essentially &quot;floats.&quot; The motor driver cannot accurately determine what constitutes a logic HIGH (3.3V) or a logic LOW (0V), meaning the motors won&#x27;t activate.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;XDPilbXST54&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Right Motor Driver Test (Elevated)&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;5jg_x6OLH68&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Right Motor Driver Test (Elevated)&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;hbjFIpIejHI&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Both Motors Running on Power Supply&lt;&#x2F;figcaption&gt;
&lt;p&gt;Once both sides were verified, I transitioned power from the bench supply to the 3.7V 850mAh battery to ensure the system could run untethered.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;towbY2_A_A4&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Both Motors Running on Battery Power&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;complete-hardware-integration-on-car&quot;&gt;Complete Hardware Integration on Car&lt;&#x2F;h3&gt;
&lt;p&gt;All components were packed securely into the chassis. The motor drivers were zip-tied toward the center to keep wire runs to the motors short. The Artemis and IMU were mounted near the middle to keep the center of gravity balanced, and the two ToF sensors were placed to ensure clear lines of sight. I made sure no components stuck out past the wheels so the car could safely roll or flip without damaging the electronics.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;done.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Top-down view of the fully integrated chassis&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;div style=&quot;display: flex; justify-content: space-around; align-items: center; gap: 10px;&quot;&gt;
&lt;div style=&quot;text-align: center;&quot;&gt;
&lt;img src=&quot;done_right.jpg&quot; style=&quot;max-width: 100%; height: auto;&quot;&gt;
&lt;p&gt;Right View&lt;&#x2F;p&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;text-align: center;&quot;&gt;
&lt;img src=&quot;done_l.jpg&quot; style=&quot;max-width: 100%; height: auto;&quot;&gt;
&lt;p&gt;Left View&lt;&#x2F;p&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;figcaption&gt;Side profiles of the fully integrated chassis&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;motor-functions&quot;&gt;Motor Functions&lt;&#x2F;h3&gt;
&lt;p&gt;To make testing easier for the remainder of this lab and future assignments, I integrated helper functions for motor control (&lt;code&gt;moveForward&lt;&#x2F;code&gt;, &lt;code&gt;moveBackward&lt;&#x2F;code&gt;, &lt;code&gt;turnLeft&lt;&#x2F;code&gt;, &lt;code&gt;turnRight&lt;&#x2F;code&gt;, &lt;code&gt;stopMotors&lt;&#x2F;code&gt;, and speed adjustments) into my main Artemis code. I also mapped these functions to commands sent over Bluetooth. For the sake of brevity, I haven&#x27;t included the Bluetooth parsing code here, as it was documented in the previous three labs.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; moveForward&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, motorSpeed); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, motorSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; moveBackward&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, motorSpeed);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2, motorSpeed);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; turnLeft&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, motorSpeed);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, motorSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; turnRight&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, motorSpeed); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2, motorSpeed);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; stopMotors&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;lower-pwm-limit&quot;&gt;Lower PWM Limit&lt;&#x2F;h3&gt;
&lt;p&gt;To find the minimum PWM value required to overcome the gearbox&#x27;s static friction (the &quot;deadband&quot;), I placed the car on the floor and slowly ramped up the &lt;code&gt;motorSpeed&lt;&#x2F;code&gt; variable.&lt;&#x2F;p&gt;
&lt;p&gt;On a full charge, the minimum PWM to move both forward and backward was about 40-41. In an earlier test (shown in the first video below), I decremented the PWM from high to low and found a slightly higher minimum limit of 44. This discrepancy is likely due to a lower battery charge at the time. Because PWM is a percentage of the total voltage, a dying battery provides a lower average voltage to the motors, meaning a higher PWM value is required to achieve the same physical torque.&lt;&#x2F;p&gt;
&lt;p&gt;Executing an on-axis turn required a significantly higher minimum PWM of 145. This is due to the physics of skid steering: to turn in place, the wheels are forced to drag laterally across the ground, generating vastly more static friction than moving in a straight line. It is worth noting that I conducted this turning test on a different surface with a higher coefficient of friction, so the minimum PWM for turning on the standard lab floor may be lower.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;for&lt;&#x2F;span&gt;&lt;span&gt; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; range&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;15&lt;&#x2F;span&gt;&lt;span&gt;):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;SET_SPEED&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; str&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;25&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt;i))&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;FORWARD&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    time.sleep(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # ble.send_command(CMD.BACKWARD, &amp;quot;&amp;quot;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # time.sleep(1)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # ble.send_command(CMD.LEFT, &amp;quot;&amp;quot;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # time.sleep(2)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # ble.send_command(CMD.RIGHT, &amp;quot;&amp;quot;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # time.sleep(2)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;    print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Speed set to: &lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;{25&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt;i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;}&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;STOP&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Here are the videos documenting the lower limit tests:&lt;&#x2F;p&gt;
&lt;div style=&quot;display: grid; grid-template-columns: repeat(2, 1fr); gap: 20px; text-align: center;&quot;&gt;
&lt;div&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;aNkpLh34K3s&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Decremental Limit Test with Forward and Backward&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div&gt;
&lt;video width=&quot;100%&quot; height=&quot;250&quot; controls&gt;
&lt;source src=&quot;turn_limit2.mp4&quot; type=&quot;video&#x2F;mp4&quot;&gt;
Your browser does not support the video tag.
&lt;&#x2F;video&gt;
&lt;&#x2F;div&gt;
&lt;div&gt;
&lt;video width=&quot;100%&quot; height=&quot;250&quot; controls&gt;
&lt;source src=&quot;forward_limit.mp4&quot; type=&quot;video&#x2F;mp4&quot;&gt;
Your browser does not support the video tag.
&lt;&#x2F;video&gt;
&lt;&#x2F;div&gt;
&lt;div&gt;
&lt;video width=&quot;100%&quot; height=&quot;250&quot; controls&gt;
&lt;source src=&quot;backward_limit.mp4&quot; type=&quot;video&#x2F;mp4&quot;&gt;
Your browser does not support the video tag.
&lt;&#x2F;video&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;h3 id=&quot;calibration&quot;&gt;Calibration&lt;&#x2F;h3&gt;
&lt;p&gt;Due to mechanical variances, providing the exact same PWM value to both motors caused the car to drift noticeably. To achieve a straight 2-meter run, I implemented a multiplicative calibration factor.&lt;&#x2F;p&gt;
&lt;p&gt;I started both &lt;code&gt;leftCalibration&lt;&#x2F;code&gt; and &lt;code&gt;rightCalibration&lt;&#x2F;code&gt; at &lt;code&gt;1.0&lt;&#x2F;code&gt;. After observing the car veering left (which indicates the right wheels were spinning faster and driving the chassis to the left), I iteratively increased the left calibration float down to &lt;code&gt;1.2&lt;&#x2F;code&gt;.&lt;&#x2F;p&gt;
&lt;p&gt;Because calibration multipliers can sometimes push a base speed over the maximum 8-bit PWM limit, I also implemented the &lt;code&gt;constrain()&lt;&#x2F;code&gt; function as a safety measure to prevent integer overflow.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 100&lt;&#x2F;span&gt;&lt;span&gt;; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; leftCalibration &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1.2&lt;&#x2F;span&gt;&lt;span&gt;;  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; rightCalibration &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1.0&lt;&#x2F;span&gt;&lt;span&gt;; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; moveForward&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; leftCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; rightCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualLeftSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualRightSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, actualLeftSpeed); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, actualRightSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; turnLeft&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; leftCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; rightCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualLeftSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualRightSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, actualLeftSpeed);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, actualRightSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;With the calibration applied, the car successfully followed a straight line found on the floor in Upson Hall using forward commands sent from the Python backend. You can see a massive difference in stability before and after calibration.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;start_line.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Example of the Starting Point&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;video width=&quot;640&quot; height=&quot;360&quot; controls&gt;
&lt;source src=&quot;cal1.mp4&quot; type=&quot;video&#x2F;mp4&quot;&gt;
Your browser does not support the video tag.
&lt;&#x2F;video&gt;
&lt;video width=&quot;640&quot; height=&quot;360&quot; controls&gt;
&lt;source src=&quot;cal2.mp4&quot; type=&quot;video&#x2F;mp4&quot;&gt;
Your browser does not support the video tag.
&lt;&#x2F;video&gt;
&lt;h2 id=&quot;open-loop-testing&quot;&gt;Open Loop Testing&lt;&#x2F;h2&gt;
&lt;video width=&quot;640&quot; height=&quot;360&quot; controls&gt;
&lt;source src=&quot;open_loop.mp4&quot; type=&quot;video&#x2F;mp4&quot;&gt;
Your browser does not support the video tag.
&lt;&#x2F;video&gt;
&lt;h2 id=&quot;discussion&quot;&gt;Discussion&lt;&#x2F;h2&gt;
&lt;p&gt;Although this lab report is shorter compared to previous ones, the lab itself has definitely taken the most amount of time. From soldering the full circuit (which took way longer than anticipated), to testing the PWM signals and overcoming the grounding roadblocks, to iteratively calibrating the robot to drive in a straight line, it was a heavy workload.&lt;&#x2F;p&gt;
&lt;p&gt;Despite the calibration, the open-loop drive is still not perfect. It is prone to slipping and drifting over long distances, which really highlights the limitations of relying purely on dead reckoning. I am looking forward to implementing PID control using sensor feedback for much better reliability in the future.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h2&gt;
&lt;p&gt;I collaborated extensively on this project with Ananya Jajodia and Dyllan Hofflich.&lt;&#x2F;p&gt;
&lt;p&gt;I referenced Aiden Derocher&#x27;s site for wiring help and PWM testing.&lt;&#x2F;p&gt;
&lt;p&gt;ChatGPT was used for some website formatting.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 4: Motor Drivers and Open Loop Control</title>
          <pubDate>Mon, 02 Mar 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-4/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-4/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-4/">&lt;h2 id=&quot;prelab&quot;&gt;Prelab&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;wire-schematic&quot;&gt;Wire Schematic&lt;&#x2F;h3&gt;
&lt;p&gt;To control the motors, I utilized the PWM-capable pins on the Artemis Nano. I refer to Lucca Correial&#x27;s website for identify which pins can do PWM. I assigned pins 15 and 14 for the Left Motor (forward and backward, respectively) and 2 and 3 for the Right Motor. These pins were chosen to keep the wiring organized and relatively localized on the board.&lt;&#x2F;p&gt;
&lt;p&gt;From lecture and further research, parallel-couple the inputs and outputs of each dual motor driver ensure the motors receive enough current without overheating the motor drivers. This effectively combines the two channels of a single IC, doubling the average current capacity sent to each DC motor.&lt;&#x2F;p&gt;
&lt;p&gt;Here is my full circuit schematic include work from lab 1-4.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;wire_diagram.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;System Circuit Schematic&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h3 id=&quot;battery-discussion&quot;&gt;Battery Discussion&lt;&#x2F;h3&gt;
&lt;p&gt;We use two separate batteries—one for the Artemis and one for the motor drivers—to isolate our logic circuitry from electrical noise and voltage drops. DC motors are significant inductive loads; when they rapidly change speed or reverse direction, they can pull large spikes of current and generate back-EMF. If the Artemis were powered by the same supply, these fluctuations could cause the microcontroller to brown-out, reset, or register false readings on the sensors.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;lab-tasks&quot;&gt;Lab Tasks&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;soldering-the-circuit&quot;&gt;Soldering the Circuit&lt;&#x2F;h3&gt;
&lt;p&gt;Below is an image of the finished, soldered physical circuit. (Note: The circuit had not been mounted into the chassis before my initial PWM tests; I just forgot to photograph it prior to this step!)&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;physical_circuit.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Finished System Circuit&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h3 id=&quot;power-supply-and-oscilloscope-hookup&quot;&gt;Power Supply and Oscilloscope Hookup&lt;&#x2F;h3&gt;
&lt;p&gt;Before integrating the drivers into the car, I tested the PWM outputs using an oscilloscope and an external power supply. The power supply was set to 3.7V with a conservative current limit to simulate the 850mAh Li-Ion battery, which prevents any real damage in the event of a short circuit or a bad soldering job.&lt;&#x2F;p&gt;
&lt;p&gt;Here is the image of the setup:&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;IMG_7946.PNG&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Oscilloscope Hookup&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;IMG_7947.PNG&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Power Supply Hookup&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;To verify the PWM generation, I used the following basic code to send a duty cycle of approximately 23% (60&#x2F;255) to pin 15, representing the forward direction:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;#define&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; MOTOR_INL1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 15&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;#define&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; MOTOR_INL2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 14&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; setup&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  pinMode&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, OUTPUT);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  pinMode&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, OUTPUT);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; loop&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 60&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Here is video showing my probe setup, as well as the results:&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;MVw43_S0BW8&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Left Motor Driver PWM Test&lt;&#x2F;figcaption&gt;
&lt;p&gt;The analogWrite(MOTOR_INL1,60) line indicated a 23.5% (60&#x2F;255) duty cycle to pin 15. Oscilloscope graph:&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;oscilloscope1.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Oscilloscope capturing the PWM signal&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;Now I used a for loop to incrementally increase the PWM from 0 to 255 on the left motor, and this is a video showing this:&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;DooZhPy4oLc&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Regulated Left Motor Driver PWM Test&lt;&#x2F;figcaption&gt;
&lt;p&gt;Here is the example graph for the PWM being regulated:&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;oscilloscope2.PNG&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Oscilloscope capturing the PWM signal&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;Switch to the right motor, and do the same regulating test:&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;LsvBeuKERr4&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Regulated Right Motor Driver PWM Test&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;motor-testing&quot;&gt;Motor Testing&lt;&#x2F;h3&gt;
&lt;p&gt;After validating the signal, I dismantled the RC car. I decided not to remove the stock PCB, thinking the flat surface would be useful for mounting my components (although I ultimately didn&#x27;t take much advantage of it for this lab). I then cut the motor leads and wired up the left motor driver first, keeping the chassis elevated so the wheels could spin freely.&lt;&#x2F;p&gt;
&lt;p&gt;During this phase, I ran into a frustrating bug while testing the second motor driver. I wrote the exact same PWM code to verify the motor functioned correctly, I can also the motor try to spin from the hum sound, but it refused to spin. After extensive troubleshooting, I finally connected the &lt;code&gt;VIN&lt;&#x2F;code&gt; and &lt;code&gt;GND&lt;&#x2F;code&gt; leads of both motor drivers together into the power supply, and it worked perfectly—even though I was only actively controlling one driver.&lt;&#x2F;p&gt;
&lt;p&gt;Here is some of the results of the PWM test on actual motors:&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;XDPilbXST54&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Right Motor Driver Test (Elevated)&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;5jg_x6OLH68&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Right Motor Driver Test (Elevated)&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;hbjFIpIejHI&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Both Motors Running on Power Supply&lt;&#x2F;figcaption&gt;
&lt;p&gt;Once both sides were verified, I transitioned power from the bench supply to the 3.7V 850mAh battery to ensure the system could run untethered.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;towbY2_A_A4&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Both Motors Running on Battery Power&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;complete-hardware-integration-on-car&quot;&gt;Complete Hardware Integration on Car&lt;&#x2F;h3&gt;
&lt;p&gt;All components were packed securely into the chassis. The IMU were zip-tied in the front of the bot on the flat surface of the battery case. The motor drivers sits a bit back from there. I put both batteries in the battery case. The Artemis is mounted in the back of the car, and the two ToF sensors were placed in the front and the left side to ensure clear lines of sight. In this way, I try to keep all the high voltage component away from the sensors, try to keep the EMI as low as possible. I made sure no components stuck out past the wheels so the car could safely roll or flip without damaging the electronics. (Failed driving tests, ie. running into the wall, have shown, this is indeed reliable.)&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;done.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Top-down view of the fully integrated chassis&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;div style=&quot;display: flex; justify-content: space-around; align-items: center; gap: 10px;&quot;&gt;
&lt;div style=&quot;text-align: center;&quot;&gt;
&lt;img src=&quot;done_right.jpg&quot; style=&quot;max-width: 100%; height: auto;&quot;&gt;
&lt;p&gt;Right View&lt;&#x2F;p&gt;
&lt;&#x2F;div&gt;
&lt;div style=&quot;text-align: center;&quot;&gt;
&lt;img src=&quot;done_l.jpg&quot; style=&quot;max-width: 100%; height: auto;&quot;&gt;
&lt;p&gt;Left View&lt;&#x2F;p&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;figcaption&gt;Side profiles of the fully integrated chassis&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;motor-functions&quot;&gt;Motor Functions&lt;&#x2F;h3&gt;
&lt;p&gt;To make testing easier for the remainder of this lab and future assignments, I integrated helper functions for motor control (&lt;code&gt;moveForward&lt;&#x2F;code&gt;, &lt;code&gt;moveBackward&lt;&#x2F;code&gt;, &lt;code&gt;turnLeft&lt;&#x2F;code&gt;, &lt;code&gt;turnRight&lt;&#x2F;code&gt;, &lt;code&gt;stopMotors&lt;&#x2F;code&gt;, and speed adjustments) into my main Artemis code. I also mapped these functions to commands sent over Bluetooth. For the sake of brevity, I haven&#x27;t included the Bluetooth parsing code here, as it was documented in the previous three labs.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; moveForward&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, motorSpeed); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, motorSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; moveBackward&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, motorSpeed);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2, motorSpeed);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; turnLeft&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, motorSpeed);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, motorSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; turnRight&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, motorSpeed); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2, motorSpeed);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; stopMotors&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;lower-pwm-limit&quot;&gt;Lower PWM Limit&lt;&#x2F;h3&gt;
&lt;p&gt;To find the minimum PWM value required to overcome the gearbox&#x27;s static friction (the &quot;deadband&quot;), I placed the car on the floor and slowly ramped up the &lt;code&gt;motorSpeed&lt;&#x2F;code&gt; variable.&lt;&#x2F;p&gt;
&lt;p&gt;On a full charge, the minimum PWM to move both forward and backward was about 40-41. In an earlier test (shown in the first video below), I decremented the PWM from high to low and found a slightly higher minimum limit of 44. This discrepancy is likely due to a lower battery charge at the time. Because PWM is a percentage of the total voltage, a dying battery provides a lower average voltage to the motors, meaning a higher PWM value is required to achieve the same physical torque.&lt;&#x2F;p&gt;
&lt;p&gt;Executing an on-axis turn required a significantly higher minimum PWM of 135. This is due to the physics of skid steering: to turn in place, the wheels are forced to drag laterally across the ground, generating vastly more static friction than moving in a straight line. It is worth noting that I conducted this turning test on a different surface with a higher coefficient of friction, so the minimum PWM for turning on the standard lab floor may be lower.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;for&lt;&#x2F;span&gt;&lt;span&gt; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; range&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;15&lt;&#x2F;span&gt;&lt;span&gt;):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;SET_SPEED&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; str&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;25&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt;i))&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;FORWARD&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    time.sleep(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # ble.send_command(CMD.BACKWARD, &amp;quot;&amp;quot;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # time.sleep(1)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # ble.send_command(CMD.LEFT, &amp;quot;&amp;quot;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # time.sleep(2)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # ble.send_command(CMD.RIGHT, &amp;quot;&amp;quot;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    # time.sleep(2)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;    print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Speed set to: &lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;{25&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt;i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;}&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;STOP&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Here are the videos documenting the lower limit tests:&lt;&#x2F;p&gt;
&lt;div style=&quot;display: grid; grid-template-columns: repeat(2, 1fr); gap: 20px; text-align: center;&quot;&gt;
&lt;div&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;aNkpLh34K3s&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Decremental Limit Test with Forward and Backward&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;_9iMhKC3L0A&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Turning Limit Test&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;2j2Tr3IEzgk&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Forward Limit Test&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;div&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;zOV7ENlsKYM&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Backward Limit Test&lt;&#x2F;figcaption&gt;
&lt;&#x2F;div&gt;
&lt;&#x2F;div&gt;
&lt;h3 id=&quot;calibration&quot;&gt;Calibration&lt;&#x2F;h3&gt;
&lt;p&gt;Due to mechanical variances, providing the exact same PWM value to both motors caused the car to drift noticeably. To achieve a straight 2-meter run, I implemented a multiplicative calibration factor.&lt;&#x2F;p&gt;
&lt;p&gt;I started both &lt;code&gt;leftCalibration&lt;&#x2F;code&gt; and &lt;code&gt;rightCalibration&lt;&#x2F;code&gt; at &lt;code&gt;1.0&lt;&#x2F;code&gt;. After observing the car veering left (which indicates the right wheels were spinning faster and driving the chassis to the left), I iteratively increased the left calibration float down to &lt;code&gt;1.2&lt;&#x2F;code&gt;.&lt;&#x2F;p&gt;
&lt;p&gt;Because calibration multipliers can sometimes push a base speed over the maximum 8-bit PWM limit, I also implemented the &lt;code&gt;constrain()&lt;&#x2F;code&gt; function as a safety measure to prevent integer overflow.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 100&lt;&#x2F;span&gt;&lt;span&gt;; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; leftCalibration &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1.2&lt;&#x2F;span&gt;&lt;span&gt;;  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; rightCalibration &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1.0&lt;&#x2F;span&gt;&lt;span&gt;; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; moveForward&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; leftCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; rightCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualLeftSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualRightSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1, actualLeftSpeed); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, actualRightSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; turnLeft&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; leftCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  int&lt;&#x2F;span&gt;&lt;span&gt; actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; motorSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; rightCalibration;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualLeftSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualLeftSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  actualRightSpeed &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; constrain&lt;&#x2F;span&gt;&lt;span&gt;(actualRightSpeed,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 255&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL1,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INL2, actualLeftSpeed);   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR1, actualRightSpeed);  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;  analogWrite&lt;&#x2F;span&gt;&lt;span&gt;(MOTOR_INR2,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;With the calibration applied, the car successfully followed a straight line found on the floor in Upson Hall using forward commands sent from the Python backend. You can see a massive difference in stability before and after calibration.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;start_line.jpg&quot; alt=&quot;circuit&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Example of the Starting Point&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;761I6qX16ww&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Straight Test Before Calibration&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;Fx5qrLB3bY8&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Straight Test After Calibration&lt;&#x2F;figcaption&gt;
&lt;h2 id=&quot;open-loop-testing&quot;&gt;Open Loop Testing&lt;&#x2F;h2&gt;
&lt;p&gt;Finally, I try to move the car in a race track manner, by have it move forward, turn left, move around the curve, turn left, move forward again, then turn. In general this drive is not great, but it achieve its goal.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;100%&quot; height=&quot;250&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;8wYWEQr-wOY&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;Open Loop Test&lt;&#x2F;figcaption&gt;
&lt;h2 id=&quot;discussion&quot;&gt;Discussion&lt;&#x2F;h2&gt;
&lt;p&gt;Although this lab report is shorter compared to previous ones, the lab itself has definitely taken the most amount of time. From soldering the full circuit (which took way longer than anticipated), to testing the PWM signals and overcoming the grounding roadblocks, to iteratively calibrating the robot to drive in a straight line, it was a heavy workload.&lt;&#x2F;p&gt;
&lt;p&gt;Despite the calibration, the open-loop drive is still not perfect. It is prone to slipping and drifting over long distances, which really highlights the limitations of relying purely on dead reckoning. I am looking forward to implementing PID control using sensor feedback for much better reliability in the future.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h2&gt;
&lt;p&gt;I collaborated extensively on this project with Ananya Jajodia and Dyllan Hofflich.&lt;&#x2F;p&gt;
&lt;p&gt;I referenced Aiden Derocher&#x27;s site for wiring help and PWM testing.&lt;&#x2F;p&gt;
&lt;p&gt;ChatGPT was used for some website formatting.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 3: Time of Flight Sensors</title>
          <pubDate>Mon, 23 Feb 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-3/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-3/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-3/">&lt;h2 id=&quot;overview&quot;&gt;Overview&lt;&#x2F;h2&gt;
&lt;p&gt;In Lab 3, the objective was to test out the functionalities and capabilities of two VL53L1X Time-of-Flight (ToF) sensors while still having the IMU. The faster and more reliably the robot can sample these distances, the faster it can safely drive. This lab involved permanently wiring the sensors, powering the Artemis from a battery, bypassing I2C address conflicts, and streaming accurate and reliable ToF data over Bluetooth alongside the IMU.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;sensor-placement-strategy&quot;&gt;Sensor Placement Strategy&lt;&#x2F;h3&gt;
&lt;p&gt;I plan to mount one ToF sensor on the front center of the car to detect obstacles directly in the driving path, and the other on the side of the car between the wheels. This configuration will allow the robot to avoid forward collisions while simultaneously maintaining a set distance from the sides for tasks, based on what I know from future labs.&lt;&#x2F;p&gt;
&lt;p&gt;&lt;strong&gt;Blind spots:&lt;&#x2F;strong&gt; Because the sensors have a relatively narrow Field of View, the robot will likely miss obstacles that are lower than the sensor&#x27;s mounting height, highly reflective&#x2F;angled surfaces that bounce the IR light away, or thin obstacles that fall between the front and side sensor&#x27;s cone of vision.  These blind spots will need to be taken into great consideration in the future when I am doing localization.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;i2c-address-conflict&quot;&gt;I2C Address Conflict&lt;&#x2F;h3&gt;
&lt;p&gt;Using the &lt;code&gt;Example05_Wire_I2C.ino&lt;&#x2F;code&gt; sketch, I scanned the bus and successfully found the default ToF at address &lt;code&gt;0x29&lt;&#x2F;code&gt;, and the IMU at address &lt;code&gt;0x69&lt;&#x2F;code&gt; on port &lt;code&gt;0x10000E9C&lt;&#x2F;code&gt;. I determined those numbers specifically by doing isolation tests on the sensors.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;I2C_tof.jpg&quot; alt=&quot;I2C Scanner Output&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;I2C Device Scanning with only the Time of Flight plugged in&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;I2C_imu.jpg&quot; alt=&quot;I2C Scanner Output&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;I2C Device Scanning with both the Time of Flight and IMU plugged in&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;Both VL53L1X sensors share the same hardwired default I2C address (&lt;code&gt;0x29&lt;&#x2F;code&gt;). This was a bit unexpected, because its datasheet said that the default address is &lt;code&gt;0x52&lt;&#x2F;code&gt;. After further investigation, I realized that the address is left-shifted by 1 bit, since the LSB is used for read&#x2F;write. Since I2C requires unique addresses for each device on the bus, I cannot simply plug both into the Qwiic connector and work with both of them simultaneously.&lt;&#x2F;p&gt;
&lt;p&gt;To solve this, I used the &lt;code&gt;XSHUT&lt;&#x2F;code&gt; (shutdown) pin. By wiring the &lt;code&gt;XSHUT&lt;&#x2F;code&gt; pin of ToF sensor 2 to an output pin on the Artemis (Pin A0), I can hold Sensor 2 in hardware shutdown during boot. I then initialize Sensor 1, use software to change its address to &lt;code&gt;0x30&lt;&#x2F;code&gt;, and finally pull &lt;code&gt;XSHUT&lt;&#x2F;code&gt; high to wake up Sensor 2 at the default &lt;code&gt;0x29&lt;&#x2F;code&gt; address. The following is the code that implements what I described above.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    WIRE_PORT.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;begin&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    WIRE_PORT.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;setClock&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;400000&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;println&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Booting ToF Sensors...&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    pinMode&lt;&#x2F;span&gt;&lt;span&gt;(SHUTDOWN_PIN, OUTPUT);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    digitalWrite&lt;&#x2F;span&gt;&lt;span&gt;(SHUTDOWN_PIN, LOW); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    delay&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;50&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;begin&lt;&#x2F;span&gt;&lt;span&gt;(); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;setI2CAddress&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;0x&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;30&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    digitalWrite&lt;&#x2F;span&gt;&lt;span&gt;(SHUTDOWN_PIN, HIGH);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    delay&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;50&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;begin&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;setDistanceModeShort&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;setDistanceModeLong&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h2 id=&quot;hardware-setup&quot;&gt;Hardware Setup&lt;&#x2F;h2&gt;
&lt;p&gt;I prepared the Artemis by soldering the provided 650mAh RC car battery to a JST jumper cable. I was careful to cut and strip the wires one at a time to avoid shorting the battery. After soldering, I used heat shrink tubing to insulate the exposed wire. I verified the polarity (positive to positive) before plugging it into the Artemis.&lt;&#x2F;p&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;soldered_battery.jpg&quot; style=&quot;width:300px;&quot;&gt;
&lt;figcaption&gt;Soldered Battery&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;I then successfully tested this by running my BLE Python script and sending some test messages back and forth without the USB-C cable connected.&lt;&#x2F;p&gt;
&lt;div style=&quot;display:flex; gap:15px; justify-content:center; flex-wrap:wrap;&quot;&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;verf_python.jpg&quot; style=&quot;width:300px;&quot;&gt;
&lt;figcaption&gt;Python server on messaging tests on battery&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;verf_art.jpg&quot; style=&quot;width:300px;&quot;&gt;
&lt;figcaption&gt;Artemis on messaging tests on battery&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;p&gt;Finally, I cut one end off of 2 Qwiic cables and soldered one to each of the ToF sensors, noting the color coding (Blue = SDA, Yellow = SCL, Red = 3.3V, Black = GND). And I connected them to the Qwiic connector hub, as shown below in the circuit diagram.&lt;&#x2F;p&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;circuit_diagram.jpg&quot; style=&quot;width:400px;&quot;&gt;
&lt;figcaption&gt;Circuit Diagram&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h2 id=&quot;sensor-modes-dual-sensor-integration-testing&quot;&gt;Sensor Modes, Dual Sensor Integration &amp;amp; Testing&lt;&#x2F;h2&gt;
&lt;p&gt;The VL53L1X technically supports three distance modes:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;&lt;strong&gt;Short:&lt;&#x2F;strong&gt; Max distance ~1.3m. Better ambient light immunity.&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Medium:&lt;&#x2F;strong&gt; Max distance ~3m.&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Long:&lt;&#x2F;strong&gt; Max distance ~4m. Default mode, but highly sensitive to ambient light and lower accuracy at close range.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;&lt;strong&gt;The Medium Mode:&lt;&#x2F;strong&gt; I decided to ignore the medium mode for this lab, since it is supported only through the Pololu VL53L1X Library, which would require me to change a lot of the code for the ToF. If I find that I may need something in between short and long mode in the future, I will consider looking at this more carefully.&lt;&#x2F;p&gt;
&lt;p&gt;Below is the initial test I did after hooking up both of the ToF sensors and having them both function simultaneously. Note this satisfies Task 8, so I jumped ahead. Refer to the code snippet in the I2C Address section for how I got both of them to work.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;NNu_KvDo6iw&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Two ToF test&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;TP_kfJYFPFA&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Serial Monitor - Two ToF test&lt;&#x2F;figcaption&gt;
&lt;h2 id=&quot;tof-sensor-speed-and-non-blocking-code&quot;&gt;ToF Sensor Speed and Non-Blocking Code&lt;&#x2F;h2&gt;
&lt;p&gt;In future labs, the robot cannot hang while waiting for a laser to bounce back. To ensure the code executes as fast as possible, I wrote a non-blocking loop that continuously printed the Artemis &lt;code&gt;millis()&lt;&#x2F;code&gt; clock, and only printed ToF data when &lt;code&gt;checkForDataReady()&lt;&#x2F;code&gt; was true.&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;Loop Execution Speed: The &lt;code&gt;millis()&lt;&#x2F;code&gt; timestamps incremented every 3 to 4 ms, indicating that the main loop executes at roughly 250 to 330 Hz.&lt;&#x2F;li&gt;
&lt;li&gt;Sampling Rate: Sensor 1 (~46.5 Hz): Looking at some sample data, averaging those gives roughly 21.5 ms per sample, which means Sensor 1 is operating at an average rate of 46.5 Hz. Sensor 2 (~11 Hz): Sensor 2 only gets data once while Sensor 1 gets data 4 times; it is visually obvious it is running much slower.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;div style=&quot;display:flex; gap:15px; justify-content:center; flex-wrap:wrap;&quot;&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;speed1.jpg&quot; style=&quot;width:300px;&quot;&gt;
&lt;figcaption&gt;Speed test 1&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;speed2.jpg&quot; style=&quot;width:300px;&quot;&gt;
&lt;figcaption&gt;Speed test 2&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;ul&gt;
&lt;li&gt;Sensor Discrepancies: During testing, Sensor 1 sampled significantly faster than Sensor 2. This is because I set Sensor 1 to short mode and Sensor 2 to long mode. Because long mode can reach further, its waves also take longer to travel back.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;&#x2F;&#x2F; print code&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; loop&lt;&#x2F;span&gt;&lt;span&gt;() {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Time (ms): &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;println&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;millis&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  if&lt;&#x2F;span&gt;&lt;span&gt; (sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;checkForDataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    int&lt;&#x2F;span&gt;&lt;span&gt; dist1 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;getDistance&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clearInterrupt&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&amp;gt;&amp;gt;&amp;gt;&amp;gt; SENSOR 1 READY: &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(dist1);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;println&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot; mm&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  if&lt;&#x2F;span&gt;&lt;span&gt; (sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;checkForDataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    int&lt;&#x2F;span&gt;&lt;span&gt; dist2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;getDistance&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clearInterrupt&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&amp;gt;&amp;gt;&amp;gt;&amp;gt; SENSOR 2 READY: &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(dist2);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;println&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot; mm&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h2 id=&quot;data-collection-over-bluetooth&quot;&gt;Data Collection over Bluetooth&lt;&#x2F;h2&gt;
&lt;p&gt;First, I wanted to compare the performance difference between the long mode and short mode for the ToF by starting from a white wall, and then slowly dragging my ToF sensors back from the wall for 30+ seconds.&lt;&#x2F;p&gt;
&lt;p&gt;Here are the results I got: (Note: I collected 2 trials of each for consistency comparison).&lt;&#x2F;p&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;short1.jpg&quot; style=&quot;width:400px;&quot;&gt;
&lt;figcaption&gt;TOF short mode test 1&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;short2.jpg&quot; style=&quot;width:400px;&quot;&gt;
&lt;figcaption&gt;TOF short mode test 2 &lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;long1.jpg&quot; style=&quot;width:400px;&quot;&gt;
&lt;figcaption&gt;TOF long mode test 1&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;long2.jpg&quot; style=&quot;width:400px;&quot;&gt;
&lt;figcaption&gt;TOF long mode test 2&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h3 id=&quot;metric-evaluation&quot;&gt;Metric Evaluation:&lt;&#x2F;h3&gt;
&lt;p&gt;Range:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;Short Mode: The graphs show a perfectly linear tracking line that abruptly drops to 0 mm just past 2100 mm (~2.1 meters). This defines the absolute maximum physical range in short mode before the sensor&#x27;s confidence threshold fails. This is higher than expected from the short mode.&lt;&#x2F;li&gt;
&lt;li&gt;Long Mode: The sensors track linearly up to approximately 4800 mm (~4.8 meters). Beyond this point, the signal breaks down into massive noise spikes (erratically jumping between 0 and 5000 mm). And the noise becomes really bad starting at ~4.2 meters. But this is again higher than expected for long mode.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;Accuracy: Across all four graphs, Sensor 1 (blue) and Sensor 2 (red) overlap almost perfectly during the valid range window. The steady, linear slope as the distance increases demonstrates that the sensors scale proportionally and accurately with real-world distance, with minimal deviation between the two physical units.&lt;&#x2F;p&gt;
&lt;p&gt;Repeatability: The sensor performance is incredibly consistent. Comparing Short 1 to Short 2, both trials hit their failure point at the exact same ~2100 mm mark. Similarly, Long 1 and Long 2 both experience total signal breakdown at the identical ~4800 mm threshold. The noise profiles and slopes are virtually indistinguishable between trials.&lt;&#x2F;p&gt;
&lt;p&gt;Ranging Time: There is a direct trade-off between range and speed. Short mode allows for a much tighter timing budget (20ms), yielding a fast ranging time of approximately ~45 Hz. To achieve the 4+ meter range in Long mode, the sensors require a larger timing budget (50ms) to leave the optical shutter open longer, reducing the ranging speed to roughly ~20 Hz.&lt;&#x2F;p&gt;
&lt;p&gt;From this experiment, I decided to test the accuracy further by measuring a set distance. I made a setup with a measuring tape, using the provided white board as an object to detect and my box to hold the sensor in one position, with the tape measure recording the right distance, imaged below:&lt;&#x2F;p&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;setup.jpg&quot; style=&quot;width:400px;&quot;&gt;
&lt;figcaption&gt;Setup&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h3 id=&quot;tof-accuracy-analysis-static-distance-tests&quot;&gt;ToF Accuracy Analysis (Static Distance Tests)&lt;&#x2F;h3&gt;
&lt;p&gt;I collected static data at four precise distances: 100mm, 200mm, 500mm, and 1000mm. I used a reflective whiteboard as the target. I performed these tests in both Long Mode and Short Mode to compare their performance.&lt;&#x2F;p&gt;
&lt;p&gt;100mm and 200mm Testing&lt;&#x2F;p&gt;
&lt;div style=&quot;display:flex; gap:15px; justify-content:center; flex-wrap:wrap;&quot;&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;100mm_short.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;100 mm - Short Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;100mm_long.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;100 mm - Long Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;200mm_short.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;200 mm - Short Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;200mm_long.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;200 mm - Long Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;p&gt;500mm and 1000mm Testing&lt;&#x2F;p&gt;
&lt;div style=&quot;display:flex; gap:15px; justify-content:center; flex-wrap:wrap;&quot;&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;500mm_short.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;500 mm - Short Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;500mm_long.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;500 mm - Long Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;1000mm_short.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;1000 mm - Short Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;1000mm_long.jpg&quot; style=&quot;width:100%; max-width:400px;&quot;&gt;
&lt;figcaption&gt;1000 mm - Long Mode&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;p&gt;Analyzing these graphs reveals a disparity between Short and Long mode, which is heavily exacerbated by the reflective whiteboard target:&lt;&#x2F;p&gt;
&lt;p&gt;Short Mode is Highly Accurate: Across all four distances (100mm, 200mm, 500mm, and 1000mm), Short mode performed really well. The data lines are flat, stable, and cluster very tightly around the true distance. For instance, at 1000mm, both sensors tracked cleanly between 980mm and 1000mm. At 500mm, they were nearly perfectly aligned with the 500mm mark.&lt;&#x2F;p&gt;
&lt;p&gt;Long Mode: In stark contrast, Long mode failed at close ranges. At 100mm, the Long mode data is pretty noisy, oscillating randomly between 50mm and 200mm. Even at 1000mm, Long mode under-reads the actual distance by nearly 100mm and exhibits high-frequency jitter.&lt;&#x2F;p&gt;
&lt;p&gt;Now, this is a bit unfair for long mode because it is designed to look for faint signals from up to 4 meters away, so it increases its sensitivity and leaves its optical &quot;shutter&quot; open longer. Pointing this highly sensitive mode at a glossy, highly reflective whiteboard at a close distance of 100mm effectively &quot;blinds&quot; the sensor.&lt;&#x2F;p&gt;
&lt;p&gt;Sensor Offset: I also observed a slight, consistent offset between Sensor 1 and Sensor 2. Because the physical test setup was identical, this minor variance is likely due to the placement of my ToFs at slightly different angles, causing them to hit the whiteboard at very slightly different angles.&lt;&#x2F;p&gt;
&lt;p&gt;Conclusion: These tests definitively prove that for a small room with a lot of reflection, Short Mode wins because of its accuracy and speed. Long mode&#x27;s sensitivity to reflection makes it untrustworthy at sub-1-meter distances in this specific environment. However, if future labs require greater than 2 meter distance detection, I would need to use Long mode or implement Medium mode.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;imu-and-tof&quot;&gt;IMU and ToF&lt;&#x2F;h3&gt;
&lt;p&gt;I created a new Bluetooth command (&lt;code&gt;START_BOTH&lt;&#x2F;code&gt;) that simultaneously collects data from the ToF sensors and the IMU (using the Complementary Filter developed in Lab 2).&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        case&lt;&#x2F;span&gt;&lt;span&gt; START_BOTH: {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            recordBoth &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; true&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tof_sample_idx &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            s1_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; false&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            s2_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; false&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            temp_dist1 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            temp_dist2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;            &#x2F;&#x2F; Reset IMU timing so filters start fresh&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            imu_samples &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            t_start_us &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            t_last_us  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; t_start_us;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            imu_state_initialized &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; false&lt;&#x2F;span&gt;&lt;span&gt;; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clear&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;BOTH_RECORDING_STARTED&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_characteristic_string.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;writeValue&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; loop&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;{&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    BLEDevice central &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; BLE.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;central&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (central) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        while&lt;&#x2F;span&gt;&lt;span&gt; (central.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;connected&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            loop_count&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;;   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;            &#x2F;&#x2F; Non-blocking IMU calculation runs if requested&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            if&lt;&#x2F;span&gt;&lt;span&gt; ((recordIMU &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;||&lt;&#x2F;span&gt;&lt;span&gt; recordBoth)) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                if&lt;&#x2F;span&gt;&lt;span&gt; (myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;dataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;                    collectIMU&lt;&#x2F;span&gt;&lt;span&gt;();          &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;            &#x2F;&#x2F; Non-blocking ToF sampling &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            if&lt;&#x2F;span&gt;&lt;span&gt; ((recordToF &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;||&lt;&#x2F;span&gt;&lt;span&gt; recordBoth)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &amp;amp;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt; tof_sample_idx &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; MAX_SAMPLES) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Throttle I2C polling to every 5ms&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                static uint32_t&lt;&#x2F;span&gt;&lt;span&gt; last_tof_check &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;micros&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; last_tof_check &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 5000&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    last_tof_check &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;s1_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;amp;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt; sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;checkForDataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        temp_dist1 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;getDistance&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        sensor1.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clearInterrupt&lt;&#x2F;span&gt;&lt;span&gt;(); &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        s1_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; true&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;s2_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;amp;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt; sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;checkForDataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        temp_dist2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;getDistance&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        sensor2.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clearInterrupt&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        s2_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; true&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                    &#x2F;&#x2F; Once BOTH sensors are ready, record everything!&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                    if&lt;&#x2F;span&gt;&lt;span&gt; (s1_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;amp;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt; s2_read_done) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        tof_time_buffer[tof_sample_idx]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        tof1_buffer[tof_sample_idx]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; temp_dist1;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        tof2_buffer[tof_sample_idx]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; temp_dist2;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                        &#x2F;&#x2F; If doing combined recording, grab the most recent IMU state&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                        if&lt;&#x2F;span&gt;&lt;span&gt; (recordBoth) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                            pitchcomp_buffer[tof_sample_idx]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; pitch_comp_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                            rollcomp_buffer[tof_sample_idx]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  =&lt;&#x2F;span&gt;&lt;span&gt; roll_comp_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        tof_sample_idx&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        s1_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; false&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                        s2_read_done &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; false&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;            write_data&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;            read_data&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Because the IMU calculates data much faster than the ToF sensors, the IMU updates its angles in the background continuously. Whenever the ToF sensors finish a distance reading, the Artemis grabs the &lt;em&gt;most recent&lt;&#x2F;em&gt; IMU pitch and roll and saves all five variables into parallel arrays.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;tof_imu.jpg&quot; alt=&quot;Distance vs Time&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Distance and IMU Complementary Pitch and Roll vs. Time for over 10 seconds&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;As seen in the graph above, all three sensors (2 ToFs and 1 IMU) are successfully running in parallel without blocking each other.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h2&gt;
&lt;p&gt;I collaborated extensively on this project with Ananya Jajodia.&lt;&#x2F;p&gt;
&lt;p&gt;I referenced Lucca Correia&#x27;s site for the I2C address and ToF speed test, and Aidan Derocher&#x27;s site for the wiring diagram and ToF testing.&lt;&#x2F;p&gt;
&lt;p&gt;ChatGPT was used for plotting CSV data and sending ToF data over Bluetooth.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 2: IMU</title>
          <pubDate>Tue, 10 Feb 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab2/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab2/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab2/">&lt;h2 id=&quot;overview&quot;&gt;Overview&lt;&#x2F;h2&gt;
&lt;p&gt;In Lab 2, I integrated a 9DOF IMU with the SparkFun RedBoard Artemis Nano, computed orientation estimates from accelerometer and gyroscope data, analyzed accelerometer noise in the frequency domain, implemented a low-pass filter (LPF), and fused accelerometer + gyroscope estimates with a complementary filter. Finally, I powered the RC car from a battery and recorded driving “stunts” to establish a baseline for future autonomous behavior.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;imu-setup&quot;&gt;IMU Setup&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;hardware-connections&quot;&gt;Hardware connections&lt;&#x2F;h3&gt;
&lt;p&gt;I connected the SparkFun ICM-20948 IMU breakout to the Artemis using the QWIIC connectors (I2C). The image below shows this setup. I also added a visual indicator by blinking the Artemis LED 3 times on boot; there is an image for this as well.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;imu_wiring.jpg&quot; alt=&quot;Artemis + IMU wiring&quot; style=&quot;display:block; width:300px;&quot;&gt;
&lt;figcaption&gt;Artemis + IMU wiring via QWIIC&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;Artemis_Blink.jpg&quot; alt=&quot;Artemis Blink&quot; style=&quot;display:block; width:300px;&quot;&gt;
&lt;figcaption&gt;Artemis with blue LED indicator&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h3 id=&quot;example-code-works&quot;&gt;Example code works&lt;&#x2F;h3&gt;
&lt;p&gt;I verified basic IMU functionality using the SparkFun library example:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;Library: &lt;strong&gt;SparkFun 9DoF IMU Breakout - ICM 20948 - Arduino Library&lt;&#x2F;strong&gt;&lt;&#x2F;li&gt;
&lt;li&gt;Example: &lt;code&gt;Example1_Basics&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;I modified the code in the example slightly in order to get the serial prints and plotter to work nicely. However, this didn&#x27;t impact the actual values, so there was minimal effect.
I confirmed that acceleration (mg) and gyroscope (DPS) values updated as expected while rotating and translating the board.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;zQG1ElMjfRQ&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Example Code IMU Test&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;ad0-val-what-it-is-what-it-should-be&quot;&gt;AD0_VAL (what it is + what it should be)&lt;&#x2F;h3&gt;
&lt;p&gt;&lt;code&gt;AD0_VAL&lt;&#x2F;code&gt; represents the least significant address-selection bit for the IMU’s I2C address (effectively selecting between the two possible I2C addresses depending on the AD0&#x2F;ADR pin state). In practice:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;If the IMU ADR&#x2F;AD0 line is left at its default, &lt;code&gt;AD0_VAL&lt;&#x2F;code&gt; should match that default.&lt;&#x2F;li&gt;
&lt;li&gt;If the ADR jumper is bridged&#x2F;closed, &lt;code&gt;AD0_VAL&lt;&#x2F;code&gt; must be changed accordingly.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;In my setup, &lt;code&gt;AD0_VAL = 1&lt;&#x2F;code&gt; because I am just using the default configuration.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;initial-sensor-behavior-what-changes-and-why&quot;&gt;Initial sensor behavior (what changes and why)&lt;&#x2F;h3&gt;
&lt;p&gt;From the example output and the calculated roll, pitch, and yaw values for both the accelerometer and gyroscope (shown in later videos):&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;&lt;strong&gt;Accelerometer:&lt;&#x2F;strong&gt; Changes with linear acceleration and also reflects gravity. When the board is still but tilted, the acceleration vector changes because gravity is distributed differently across axes. I also noticed that the accelerometer&#x27;s data is very noisy. This is expected, since accelerometers are highly sensitive to small vibrations, mechanical disturbances, and electrical noise.&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Gyroscope:&lt;&#x2F;strong&gt; Changes with angular velocity. When I rotate about an axis, I see a spike primarily on the corresponding gyro axis; when stationary, gyro values return to near zero. For the above example, you can see my gyroscope values stay mostly near zero because my motion is relatively slow, resulting in a small angular velocity being measured.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;Another important thing is that the parameters change based on the axis being rotated about. For example, when you rotate about the x-axis, you see that the pitch changes the most compared to the other two axes.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;accelerometer&quot;&gt;Accelerometer&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;pitch-and-roll-from-acceleration&quot;&gt;Pitch and roll from acceleration&lt;&#x2F;h3&gt;
&lt;p&gt;Using the equations from the lecture, I converted raw accelerometer readings into pitch and roll (degrees). I used &lt;code&gt;atan2()&lt;&#x2F;code&gt; for robust quadrant handling.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;#include&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;lt;math.h&amp;gt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;pitch_a &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; atan2&lt;&#x2F;span&gt;&lt;span&gt;(accX, accZ)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; M_PI;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;roll_a  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; atan2&lt;&#x2F;span&gt;&lt;span&gt;(accY, accZ)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; M_PI;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;The video below showcases how I obtained 0, -90, and 90 degrees for the pitch and roll from the accelerometer.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;uuNqYMH4rGA&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Roll and Pitch IMU Test&lt;&#x2F;figcaption&gt;
&lt;p&gt;Specifically, the 5 images below are static images of me hitting those specific angles.
As the images indicate, the accuracy of the accelerometer is pretty decent, as the values are close to their true values, but they are not super precise. I used a 2-point calibration to attempt to make it a bit better. Specifically for pitch, true 0 degrees is about 2 degrees, and true -90 degrees is about -88 degrees. This is easy to fix; you just need to add a 2-degree offset. The roll value is a bit more complicated because true 0 degrees is roughly -1.5, true -90 degrees is about -91, and true 90 degrees is about 92 degrees. Using the slope function, we get the following, where &lt;code&gt;a&lt;&#x2F;code&gt; is the slope and &lt;code&gt;b&lt;&#x2F;code&gt; is the offset:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;a &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (y2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; y1)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; (x2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; x1)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 183&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.9836065574&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;b &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; y2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; a&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt;x2 &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 90&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.9836065574&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;92&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; = -&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.4918032787&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;accuracy-of-the-accelerometer&quot;&gt;Accuracy of the accelerometer&lt;&#x2F;h3&gt;
&lt;div style=&quot;display:flex; gap:15px; justify-content:center; flex-wrap:wrap;&quot;&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;roll_pitch_0.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;0 degree - both&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;pitch_90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;pitch 90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;pitch_n90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;pitch -90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;roll_90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;roll 90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;roll_n90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;roll -90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  pitch &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; pitch &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 2&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;  roll &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.9836066&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; roll &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.4918033&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;div style=&quot;display:flex; gap:15px; justify-content:center; flex-wrap:wrap;&quot;&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;new_pitch_0.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;0 degree - pitch&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;new_roll_0.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;0 degree - roll&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;new_pitch_90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;pitch 90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;new_pitch_n90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;pitch -90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;new_roll_90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;roll 90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure style=&quot;margin:0;&quot;&gt;
&lt;img src=&quot;new_roll_n90.jpg&quot; style=&quot;width:180px;&quot;&gt;
&lt;figcaption&gt;roll -90 degree&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;&#x2F;div&gt;
&lt;p&gt;The calibrated results end up looking pretty good for pitch and roll at the different critical values.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;data-from-accelerometer&quot;&gt;Data from Accelerometer&lt;&#x2F;h3&gt;
&lt;p&gt;I made a new command in the Artemis code to collect the IMU sensor data with a certain number of samples (in this case, 2048 samples) and transmit them to the Python server. Once the data arrives as a string, I parse them into separate arrays by the type of data (i.e., pitch_a, roll_a, etc.). I then used them to plot graphs for analysis and results.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; GET_IMU_READINGS: {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;              float&lt;&#x2F;span&gt;&lt;span&gt; Micros &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;              float&lt;&#x2F;span&gt;&lt;span&gt; pitch &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;              float&lt;&#x2F;span&gt;&lt;span&gt; roll &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;              if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                  return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;              &#x2F;&#x2F; First, collect all data&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;              for&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; MAX_SAMPLES; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;) { &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                    while&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;dataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;getAGMT&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    Micros &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    pitch &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; atan2&lt;&#x2F;span&gt;&lt;span&gt;(myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accX&lt;&#x2F;span&gt;&lt;span&gt;(), myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accZ&lt;&#x2F;span&gt;&lt;span&gt;())&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; M_PI; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    roll  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; atan2&lt;&#x2F;span&gt;&lt;span&gt;(myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accY&lt;&#x2F;span&gt;&lt;span&gt;(), myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accZ&lt;&#x2F;span&gt;&lt;span&gt;())&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; M_PI; &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    time_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; Micros;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    roll_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; roll;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                    pitch_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; pitch;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;          }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;          &#x2F;&#x2F; Then, send the collected data&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;          for&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; x &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;; x &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; MAX_SAMPLES; x&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;) { &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clear&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(time_buffer[x]);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;:&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(pitch_buffer[x]);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;:&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(roll_buffer[x]);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              tx_characteristic_string.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;writeValue&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;          }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;          Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Done&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;          break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;          }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Then I used a similar notification handler as in Lab 1 for reading the data.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;def&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; make_notification_handler&lt;&#x2F;span&gt;&lt;span&gt;(controller):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    def&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; handler&lt;&#x2F;span&gt;&lt;span&gt;(sender:&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; int&lt;&#x2F;span&gt;&lt;span&gt;, byte_array:&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; bytearray&lt;&#x2F;span&gt;&lt;span&gt;):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        try&lt;&#x2F;span&gt;&lt;span&gt;:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            msg&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; controller.bytearray_to_string(byte_array)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            sep&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; msg.find(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;:&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            if&lt;&#x2F;span&gt;&lt;span&gt; sep&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; != -&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;: &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                times.append(msg[:sep])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                sep2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; msg.find(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;:&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;, sep&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                pitches.append(msg[sep&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;:sep2])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                rolls.append(msg[sep2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;:])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        except&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; Exception&lt;&#x2F;span&gt;&lt;span&gt;:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            msg&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; bytes&lt;&#x2F;span&gt;&lt;span&gt;(byte_array).decode(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt;errors&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;ignore&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        # Strip common C-string padding &#x2F; line endings&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        msg&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; msg.strip(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;\x00\r\n&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    return&lt;&#x2F;span&gt;&lt;span&gt; handler&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    handler&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; make_notification_handler(ble)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.stop_notify(ble.uuid[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;RX_STRING&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.start_notify(ble.uuid[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;RX_STRING&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;], handler)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;    print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Listening for notifications&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;) &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;GET_ACC_READINGS&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;) &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Here is the example plotting code I used to generate the different graphs.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;import&lt;&#x2F;span&gt;&lt;span&gt; pandas&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; as&lt;&#x2F;span&gt;&lt;span&gt; pd&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;import&lt;&#x2F;span&gt;&lt;span&gt; matplotlib.pyplot&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; as&lt;&#x2F;span&gt;&lt;span&gt; plt&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;times&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; [&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt;(t)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; for&lt;&#x2F;span&gt;&lt;span&gt; t&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span&gt; times]&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;pitches&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; [&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt;(p)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; for&lt;&#x2F;span&gt;&lt;span&gt; p&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span&gt; pitches]&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;rolls&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; [&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt;(r)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; for&lt;&#x2F;span&gt;&lt;span&gt; r&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span&gt; rolls]&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;pitches&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; [p&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; for&lt;&#x2F;span&gt;&lt;span&gt; p&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span&gt; pitches]&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;rolls&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; [(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0.9836066&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; r&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.4918033&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; for&lt;&#x2F;span&gt;&lt;span&gt; r&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span&gt; rolls]&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;t_s&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; (np.array(times)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; times[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;0&lt;&#x2F;span&gt;&lt;span&gt;])&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1000000.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;  # ms -&amp;gt; s, relative to start&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.figure(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt;figsize&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;10&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;5&lt;&#x2F;span&gt;&lt;span&gt;))&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.plot(t_s, pitches,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; label&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;Pitch&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; linewidth&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; color&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;blue&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.xlabel(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;Time (s)&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.ylabel(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;Angle (degrees)&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.title(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;IMU: Pitch vs Time&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.legend()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.grid(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;True&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.tight_layout()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.show()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.figure(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt;figsize&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;10&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;5&lt;&#x2F;span&gt;&lt;span&gt;))&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.plot(t_s, rolls,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt;  label&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;Roll&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt;  linewidth&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt; color&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;red&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.xlabel(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;Time (s)&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.ylabel(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;Angle (degrees)&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.title(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;IMU: Roll vs Time&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.legend()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.grid(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;True&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.tight_layout()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;plt.show()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;car_p_r.jpg&quot; alt=&quot;pitch and roll&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Raw pitch and roll vs. time with RC car in proximity&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;The plots above show raw accelerometer-derived pitch and roll over about 6 seconds. Both signals stay near 0° but exhibit high-frequency oscillations—roughly ±1° for both pitch and roll, indicating sensor noise and vibration from the proximity of the RC car. This raw data is what drives the use of a low-pass filter to reduce noise, which I will analyze in the next section.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;fft-and-low-pass-filter&quot;&gt;FFT and Low-Pass Filter&lt;&#x2F;h3&gt;
&lt;p&gt;I performed an FFT analysis to characterize accelerometer noise and chose a cutoff frequency for the low-pass filter.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;using-the-frequency-spectrum-to-choose-a-cutoff-frequency&quot;&gt;Using the Frequency Spectrum to Choose a Cutoff Frequency&lt;&#x2F;h2&gt;
&lt;p&gt;To determine an appropriate cutoff frequency for the low-pass filter, I analyzed the accelerometer-derived pitch and roll signals in the frequency domain using the Fast Fourier Transform (FFT). Before computing the FFT, I subtracted the mean of each signal to remove the dominant DC component caused by gravity, allowing the vibration and noise content to be more clearly observed.&lt;&#x2F;p&gt;
&lt;p&gt;The resulting frequency spectra show that the majority of the signal energy is concentrated at very low frequencies, corresponding to slow changes in orientation. Beyond this region, the spectrum becomes relatively flat and noisy, indicating high-frequency vibrations rather than meaningful motion. When the RC car was running nearby, noticeable energy appeared primarily below approximately &lt;strong&gt;0 - 8 Hz&lt;&#x2F;strong&gt;, with no strong, structured peaks at higher frequencies.&lt;&#x2F;p&gt;
&lt;p&gt;Based on this observation, I decided to pick an end value where most of that noise lies, resulting in a cutoff frequency near &lt;strong&gt;8 Hz&lt;&#x2F;strong&gt; for the low-pass filter. This cutoff preserves the low-frequency components associated with real robot motion while attenuating higher-frequency noise. Choosing a cutoff that is too low would over-smooth the signal and suppress legitimate motion (such as a quick tilt or turn), while choosing a cutoff that is too high would allow excessive vibration noise to remain in the signal.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;low-pass-filter-design-and-effect-on-the-data&quot;&gt;Low-Pass Filter Design and Effect on the Data&lt;&#x2F;h2&gt;
&lt;p&gt;To implement the low-pass filter, I used a 4th-order Butterworth filter, which provides a smooth passband and strong attenuation beyond the cutoff frequency. The filter was designed using the inferred sampling frequency of the IMU data and applied using a zero-phase &lt;code&gt;filtfilt&lt;&#x2F;code&gt; operation to avoid phase distortion.&lt;&#x2F;p&gt;
&lt;p&gt;In the time domain, the effect of the low-pass filter is clearly visible. The raw pitch and roll signals exhibit rapid, high-frequency oscillations on the order of ±1°, even when the sensor remains near a constant orientation. After filtering, these oscillations are significantly reduced, while the overall trend of the signal is preserved. This confirms that the removed components primarily correspond to noise rather than meaningful motion.&lt;&#x2F;p&gt;
&lt;p&gt;The FFT of the filtered signal further validates this choice: frequency components above the cutoff frequency are strongly attenuated, while low-frequency content remains largely unchanged. Together, the frequency-domain and time-domain results demonstrate that the selected cutoff frequency effectively balances noise reduction and signal fidelity.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;relation-to-filter-parameters-in-code&quot;&gt;Relation to Filter Parameters in Code&lt;&#x2F;h2&gt;
&lt;p&gt;The cutoff frequency directly determines the filter coefficients used in the Butterworth design. As explained in lecture, the cutoff frequency $f_c$ is related to the time constant $RC$ by&lt;&#x2F;p&gt;
&lt;p&gt;$$f_c = \frac{1}{2\pi RC}$$&lt;&#x2F;p&gt;
&lt;p&gt;and the smoothing factor $\alpha$ is related to the sampling period $T$ by&lt;&#x2F;p&gt;
&lt;p&gt;$$\alpha = \frac{T}{T + RC}$$&lt;&#x2F;p&gt;
&lt;p&gt;To solve for this theoretical value, I used this code:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;t_array&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; np.array(times)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1e6&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;fs&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; np.mean(np.diff(t_array))&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;T&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; fs&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;fc&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 5.0&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;RC&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;2&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; math.pi&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; fc)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;alpha&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; T&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; (T&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; RC&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;I got an alpha of 0.129 using the cutoff frequency of 8 Hz.
In practice, rather than explicitly computing $\alpha$, I implemented the low-pass filter using a digital Butterworth filter, which internally accounts for the sampling frequency and cutoff frequency. This approach provides a more consistent frequency response and better attenuation characteristics than a simple first-order filter.&lt;&#x2F;p&gt;
&lt;p&gt;Below are the frequency-domain plots and raw vs. LPF comparisons.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;freq_car.jpg&quot; alt=&quot;FFT with car proximity&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;FFT of accelerometer data — car in proximity&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;low_vs_org.jpg&quot; alt=&quot;Raw vs low-pass filter&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Raw vs. low-pass filtered accelerometer data&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;freq_raw_lpf.jpg&quot; alt=&quot;Freq Raw vs LPF&quot; style=&quot;display:block;width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;FFT: Raw vs. LPF&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;Additional vibration and FFT analysis:&lt;&#x2F;p&gt;
&lt;p&gt;To deliberately induce vibrational noise, I placed the IMU on the lab table and gently tapped the table with my hand. As you might notice, the peaks in the following graphs are vibration noise from those impacts—the accelerometer picks up the mechanical shock as high-frequency spikes in pitch and roll. These spikes are generated just by my finger taps. This setup helps characterize how impulsive disturbances affect the raw signal and how well the low-pass filter attenuates them. You can see that the raw signal contains a lot of vibration noise, but the low-pass filter is able to smooth them out.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;vib_p_r.jpg&quot; alt=&quot;Vibration Pitch and Roll&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Vibration Pitch and Roll — table taps&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;vib_r_p_lpf.jpg&quot; alt=&quot;Vibration freq raw vs LPF&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Vibration FFT raw vs. low-pass filtered — table-tap vibration noise&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;vib_low_org.jpg&quot; alt=&quot;Vibration raw vs LPF&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Raw vs. low-pass filtered — table-tap vibration noise&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h2 id=&quot;gyroscope&quot;&gt;Gyroscope&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;pitch-roll-and-yaw-from-gyroscope&quot;&gt;Pitch, roll, and yaw from gyroscope&lt;&#x2F;h3&gt;
&lt;p&gt;I integrated angular velocity (DPS) over time to obtain pitch, roll, and yaw angles from the gyroscope:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;delta &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;micros&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; curr_time)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1000000.0&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;curr_time &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;pitch &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; pitch &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrX&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; delta;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;roll &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; roll &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrY&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; delta;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;yaw &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; yaw  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrZ&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; delta;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h3 id=&quot;gyroscope-vs-accelerometer&quot;&gt;Gyroscope vs. accelerometer&lt;&#x2F;h3&gt;
&lt;p&gt;The gyroscope and accelerometer use different axis conventions on the ICM-20948, as we learned in lecture. The gyro pitch&#x2F;roll axes correspond to the accel roll&#x2F;pitch axes (with a sign flip for pitch). So I had to correct this mapping in the code with the following edit:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; pitch_rate &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;= -&lt;&#x2F;span&gt;&lt;span&gt;myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrY&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; roll_rate  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt;  myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrX&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;float&lt;&#x2F;span&gt;&lt;span&gt; yaw_rate   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt;  myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrZ&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;pitch_g &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+=&lt;&#x2F;span&gt;&lt;span&gt; pitch_rate &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;roll_g  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+=&lt;&#x2F;span&gt;&lt;span&gt; roll_rate  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;yaw_g   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+=&lt;&#x2F;span&gt;&lt;span&gt; yaw_rate   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;gyro_vs_acc.jpg&quot; alt=&quot;gyro vs acc&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Gyroscope vs Accelerometer in orientation&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;For the most part, the gyroscope tracks quick rotations smoothly but drifts over time due to integration error. The accelerometer is more accurate at low frequencies but is noisy. A complementary filter combines both to get a stable and accurate orientation.&lt;&#x2F;p&gt;
&lt;p&gt;Currently, I am at the highest sampling frequency with no delay. I tried putting &lt;code&gt;sleep&lt;&#x2F;code&gt; in the sample data call, which would decrease the sampling frequency. In general, the estimated angles showed increased lag and reduced responsiveness to quick motions. This makes sense because at larger time steps, you miss rapid changes, causing high-frequency vibrations to appear as low-frequency drift.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;complementary-filter&quot;&gt;Complementary Filter&lt;&#x2F;h2&gt;
&lt;p&gt;I fused the low-pass filtered accelerometer angles with the integrated gyroscope angles using a complementary filter:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;roll_comp[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  =&lt;&#x2F;span&gt;&lt;span&gt; (roll_comp[i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  +&lt;&#x2F;span&gt;&lt;span&gt; roll_G[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  *&lt;&#x2F;span&gt;&lt;span&gt; dt)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; alpha)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; rollLPF[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;  *&lt;&#x2F;span&gt;&lt;span&gt; alpha;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;pitch_comp[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; (pitch_comp[i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span&gt;]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; pitch_G[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; dt)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; -&lt;&#x2F;span&gt;&lt;span&gt; alpha)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; +&lt;&#x2F;span&gt;&lt;span&gt; pitchLPF[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span&gt; alpha;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Using an alpha of 0.05 for both the LPF and the complementary filter (which weights the gyroscope for short-term stability and the accelerometer for long-term accuracy), I got something like this:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;const float&lt;&#x2F;span&gt;&lt;span&gt; alphaLPF  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.05&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;const float&lt;&#x2F;span&gt;&lt;span&gt; alphaComp &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.05&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;first.jpg&quot; alt=&quot;Complementary filter&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Complementary filter: gyro vs. LPF accelerometer vs. fused&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;However, you might notice that the graph of the complementary filter is smooth but not very accurate, or it doesn&#x27;t respond well to changes compared to the LPF&#x27;s graph. This means I needed to increase the contribution of the accelerometer&#x27;s LPF to get a smooth and drift-corrected roll and pitch.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;const float&lt;&#x2F;span&gt;&lt;span&gt; alphaLPF  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.10&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;const float&lt;&#x2F;span&gt;&lt;span&gt; alphaComp &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.05&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;second.jpg&quot; alt=&quot;Best Complementary filter&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Best Complementary filter: gyro vs. LPF accelerometer vs. fused&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
Now this looks better!
&lt;h3 id=&quot;working-range-and-accuracy&quot;&gt;Working range and accuracy&lt;&#x2F;h3&gt;
&lt;p&gt;&lt;strong&gt;Working range:&lt;&#x2F;strong&gt; The complementary filter performs well across the typical operating range of pitch and roll—roughly ±90°. Beyond that, for these positions, the accelerometer-based angles become ill-defined (e.g., when the board is nearly vertical, the atan2 formulation approaches singularities), and the gyroscope integration accumulates more drift. This was knowledge from the microcontroller class.&lt;&#x2F;p&gt;
&lt;p&gt;&lt;strong&gt;Accuracy:&lt;&#x2F;strong&gt; With &lt;code&gt;alphaComp = 0.05&lt;&#x2F;code&gt; and &lt;code&gt;alphaLPF = 0.10&lt;&#x2F;code&gt;, the fused output tracks the LPF accelerometer really well while staying smoother than the raw accel. The filter accuracy is ultimately limited by the accelerometer (calibration, noise) at low frequencies and by the gyroscope (bias, integration error) at high frequencies. Based on my graph, however, it seems to have very good accuracy.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;sampling-data&quot;&gt;Sampling Data&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;speed-up&quot;&gt;Speed up&lt;&#x2F;h3&gt;
&lt;p&gt;I optimized the main loop to sample the IMU as fast as possible:&lt;&#x2F;p&gt;
&lt;ol&gt;
&lt;li&gt;&lt;strong&gt;Non-blocking data collection:&lt;&#x2F;strong&gt; Instead of blocking on &lt;code&gt;myICM.dataReady()&lt;&#x2F;code&gt; inside the command handler, I check &lt;code&gt;dataReady()&lt;&#x2F;code&gt; in the main loop and call &lt;code&gt;collectIMU()&lt;&#x2F;code&gt; only when new data is available. Data is stored in arrays and sent over Bluetooth in a separate command.&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Removed debug prints&lt;&#x2F;strong&gt; in the IMU read path to reduce overhead.&lt;&#x2F;li&gt;
&lt;li&gt;&lt;strong&gt;Start&#x2F;stop flags&lt;&#x2F;strong&gt; so recording only runs when requested via Bluetooth commands.&lt;&#x2F;li&gt;
&lt;&#x2F;ol&gt;
&lt;p&gt;The main loop runs much faster than the IMU produces data, so the IMU is the bottleneck. Comparing &lt;code&gt;loop_count&lt;&#x2F;code&gt; (main loop count) to &lt;code&gt;imu_samples&lt;&#x2F;code&gt; (samples collected) shows the loop cycles many times per IMU sample.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;void&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;loop&lt;&#x2F;span&gt;&lt;span&gt;()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;{&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Listen for connections&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    BLEDevice central &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; BLE.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;central&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (central) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; While central is connected&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        while&lt;&#x2F;span&gt;&lt;span&gt; (central.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;connected&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;          loop_count&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;;   &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;            &#x2F;&#x2F; Non-blocking IMU sampling&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            if&lt;&#x2F;span&gt;&lt;span&gt; (recordIMU &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;amp;&amp;amp;&lt;&#x2F;span&gt;&lt;span&gt; sample_idx &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; MAX_SAMPLES) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;              if&lt;&#x2F;span&gt;&lt;span&gt; (myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;dataReady&lt;&#x2F;span&gt;&lt;span&gt;()) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;getAGMT&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Timing&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                uint32_t&lt;&#x2F;span&gt;&lt;span&gt; now_us &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; micros&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                float&lt;&#x2F;span&gt;&lt;span&gt; dt &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; (now_us &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; t_last_us)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;e&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;6&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                t_last_us &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; now_us;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Protect against weird dt (first sample &#x2F; overflow &#x2F; etc.)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                if&lt;&#x2F;span&gt;&lt;span&gt; (dt &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; ||&lt;&#x2F;span&gt;&lt;span&gt; dt &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.1&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;) dt &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Accel -&amp;gt; pitch&#x2F;roll (deg)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                float&lt;&#x2F;span&gt;&lt;span&gt; pitch_a &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; atan2&lt;&#x2F;span&gt;&lt;span&gt;(myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accX&lt;&#x2F;span&gt;&lt;span&gt;(), myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accZ&lt;&#x2F;span&gt;&lt;span&gt;())&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; M_PI;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                float&lt;&#x2F;span&gt;&lt;span&gt; roll_a  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; atan2&lt;&#x2F;span&gt;&lt;span&gt;(myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accY&lt;&#x2F;span&gt;&lt;span&gt;(), myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;accZ&lt;&#x2F;span&gt;&lt;span&gt;())&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; *&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 180.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; M_PI;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Gyro rates (deg&#x2F;s) with your axis mapping:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                float&lt;&#x2F;span&gt;&lt;span&gt; pitch_rate &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;= -&lt;&#x2F;span&gt;&lt;span&gt;myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrY&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                float&lt;&#x2F;span&gt;&lt;span&gt; roll_rate  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt;  myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrX&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                float&lt;&#x2F;span&gt;&lt;span&gt; yaw_rate   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt;  myICM.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;gyrZ&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Initialize persistent states ONCE per recording&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;imu_state_initialized) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                  pitch_g_state &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; pitch_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                  roll_g_state  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; roll_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                  yaw_g_state   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0.0&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;f&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                  &#x2F;&#x2F; pitch_lpf_state = pitch_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                  &#x2F;&#x2F; roll_lpf_state  = roll_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                  &#x2F;&#x2F; pitch_comp_state = pitch_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                  &#x2F;&#x2F; roll_comp_state  = roll_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                  imu_state_initialized &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; true&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Integrate gyro angles&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                pitch_g_state &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+=&lt;&#x2F;span&gt;&lt;span&gt; pitch_rate &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                roll_g_state  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+=&lt;&#x2F;span&gt;&lt;span&gt; roll_rate  &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                yaw_g_state   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+=&lt;&#x2F;span&gt;&lt;span&gt; yaw_rate   &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;*&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; &#x2F;&#x2F; Low-pass accel angles&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; pitch_lpf_state = alphaLPF * pitch_a + (1.0f - alphaLPF) * pitch_lpf_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; roll_lpf_state  = alphaLPF * roll_a  + (1.0f - alphaLPF) * roll_lpf_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; &#x2F;&#x2F; Complementary filter (gyro prediction + accel correction)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; pitch_comp_state = (1.0f - alphaComp) * (pitch_comp_state + pitch_rate * dt) + alphaComp * pitch_lpf_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; roll_comp_state  = (1.0f - alphaComp) * (roll_comp_state  + roll_rate  * dt) + alphaComp * roll_lpf_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Store into arrays&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;                int&lt;&#x2F;span&gt;&lt;span&gt; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; sample_idx;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                time_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;      =&lt;&#x2F;span&gt;&lt;span&gt; now_us;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                pitch_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;     =&lt;&#x2F;span&gt;&lt;span&gt; pitch_a;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;          &#x2F;&#x2F; raw accel angle&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                roll_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;      =&lt;&#x2F;span&gt;&lt;span&gt; roll_a;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                pitchg_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    =&lt;&#x2F;span&gt;&lt;span&gt; pitch_g_state;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; integrated gyro angle&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                rollg_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;     =&lt;&#x2F;span&gt;&lt;span&gt; roll_g_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                yawg_buffer[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;      =&lt;&#x2F;span&gt;&lt;span&gt; yaw_g_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; pitchLPF_buffer[i]  = pitch_lpf_state;  &#x2F;&#x2F; filtered accel&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; rollLPF_buffer[i]   = roll_lpf_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; pitchcomp_buffer[i] = pitch_comp_state; &#x2F;&#x2F; fused&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; rollcomp_buffer[i]  = roll_comp_state;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                sample_idx&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                imu_samples&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;                &#x2F;&#x2F; Stats&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                dt_last &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; dt;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;                dt_avg &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; dt_avg &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;+&lt;&#x2F;span&gt;&lt;span&gt; (dt &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-&lt;&#x2F;span&gt;&lt;span&gt; dt_avg)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; &#x2F;&lt;&#x2F;span&gt;&lt;span&gt; imu_samples;         &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;              }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;            &#x2F;&#x2F; Send data&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;            write_data&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;            &#x2F;&#x2F; Read data&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;            read_data&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Notice I decided to only send time, raw pitch and roll from the accelerometer, and pitch, roll, and yaw from the gyroscope. This is because I could compute the low-pass filtered values and complementary values on the Python server. This design choice was made to allow me to push through more data as quickly as possible.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;data-storage&quot;&gt;Data storage&lt;&#x2F;h3&gt;
&lt;p&gt;I used separate float arrays for time (which is an int), raw accel roll&#x2F;pitch, and gyro roll&#x2F;pitch&#x2F;yaw. With 4 bytes per float (6 values) + delimiting characters (5), that is 44 bytes per sample. In particular, compared to alternative options, representing a float or int as a string takes up more space if the number is more than 4 digits. This is true for all of our data; therefore, I believe I am using the most efficient way to store these values.&lt;&#x2F;p&gt;
&lt;p&gt;Lab 2 global variables use 131,832 bytes. The Artemis has 384 kB RAM, leaving roughly 252 kB for dynamic allocation. At 44 bytes per sample, this allows storing about 5700 samples. At a ~330 Hz (see below for the calculation) sample rate, that corresponds to roughly 17 seconds of continuous IMU data.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;5-seconds-of-imu-data&quot;&gt;5 seconds of IMU data&lt;&#x2F;h3&gt;
&lt;p&gt;I collected at least 5 seconds of IMU data and sent it over Bluetooth to verify the pipeline.
This section demonstrates that I can send 5 seconds of IMU data, showing the stored IMU data array with timestamps and start&#x2F;end flags.&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;plain&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(CMD.START_IMU, &amp;quot;&amp;quot;) # start flag &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;time.sleep(5)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(CMD.STOP_IMU, &amp;quot;&amp;quot;) # end flag&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;time.sleep(0.2)               &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(CMD.SEND_IMU, &amp;quot;&amp;quot;) # actual method for sending data over BLE&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Here is the beginning and end of the csv for the data I collected for about 5.1 seconds.&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;begin.jpg&quot; alt=&quot;begin&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;Beginning of the IMU data collected for 5+ seconds&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;end.jpg&quot; alt=&quot;end&quot; style=&quot;display:block; width:100%; max-width:600px;&quot;&gt;
&lt;figcaption&gt;End of the IMU data collected for 5+ seconds&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;p&gt;There is a total of 1663 samples collected in 5 seconds, which gives about 1663 &#x2F; 5 = 332.6 Hz for data transfer.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;rc-stunts&quot;&gt;RC Stunts&lt;&#x2F;h2&gt;
&lt;p&gt;Below are videos of the RC car stunts powered by battery.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;www.youtube.com&#x2F;embed&#x2F;FyHCUjPrKYg&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;RC car stunt 1&lt;&#x2F;figcaption&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;www.youtube.com&#x2F;embed&#x2F;e-gonb3QiyY&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt;
&lt;figcaption&gt;RC car stunt 2&lt;&#x2F;figcaption&gt;
&lt;p&gt;From playing with the car, I noticed that the RC car is quick at reacting to any signal sent from the controller. I observed the car&#x27;s turning, driving straight, and drifting. It has a great self-turning mechanism if you hold down the turning trigger. I also noticed that it seems to maintain a constant speed while turning, and how easily it can be flipped over.&lt;&#x2F;p&gt;
&lt;p&gt;Bonus: I was able to get the RC car on its side and drive it with only 2 wheels on the ground. Not really useful, but I thought it was interesting.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h3&gt;
&lt;p&gt;I collaborated with: Ananya Jajodia.&lt;&#x2F;p&gt;
&lt;p&gt;I referenced: Lucca Correia&#x27;s site for FFT debugging and Sampling data section.&lt;&#x2F;p&gt;
&lt;p&gt;ChatGPT was used for: code debugging + plot generation + website formatting.&lt;&#x2F;p&gt;
</description>
      </item>
      <item>
          <title>Lab 1: Artemis and Bluetooth</title>
          <pubDate>Tue, 03 Feb 2026 00:00:00 +0000</pubDate>
          <author>Shao Stassen</author>
          <link>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-1/</link>
          <guid>https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-1/</guid>
          <description xml:base="https://shaostassen.github.io/ShaoFastRobots/Fast Robots Stuff/lab-1/">&lt;h2 id=&quot;lab-1a&quot;&gt;Lab 1A&lt;&#x2F;h2&gt;
&lt;p&gt;During section 1A, I installed the Arduino IDE and the corresponding libraries and board manager following a given tutorial and hooked up a physical connection from my computer to communicate with the SparkFun RedBoard Artemis Nano. After selecting the correct Board (RedBoard Artemis Nano) and Port, I verified programming and serial communication by running the required example sketches:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;Basics_blink&lt;&#x2F;li&gt;
&lt;li&gt;Apollo3_serial&lt;&#x2F;li&gt;
&lt;li&gt;Apollo3_analogRead&lt;&#x2F;li&gt;
&lt;li&gt;PDM_microphoneOutput&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;h3 id=&quot;blink&quot;&gt;Blink&lt;&#x2F;h3&gt;
&lt;p&gt;The Artemis board flashed its onboard LED as expected.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;sc9GYfxh8Js&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Blink test video&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;serial&quot;&gt;Serial&lt;&#x2F;h3&gt;
&lt;p&gt;The Artemis received a string over USB serial and echoed it back as I typed into the Serial Monitor, confirming serial RX&#x2F;TX.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;www.youtube.com&#x2F;embed&#x2F;2BgWrvYRqUY&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Serial communication test&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;analogread-with-temperature-sensor&quot;&gt;AnalogRead with Temperature Sensor&lt;&#x2F;h3&gt;
&lt;p&gt;The onboard temperature sensor responded to heat (touch&#x2F;breath), showing changing readings over time. In this case, I was blowing hot air to increase the temperature.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;youtube.com&#x2F;embed&#x2F;SCBCG4Kok9c&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Temperature sensor test&lt;&#x2F;figcaption&gt;
&lt;h3 id=&quot;microphone-output&quot;&gt;Microphone Output&lt;&#x2F;h3&gt;
&lt;p&gt;The PDM microphone output changed with voice&#x2F;whistle input, confirming the microphone pipeline works. In this case, I was whistling in the background to increase the sound frequency.&lt;&#x2F;p&gt;
&lt;iframe width=&quot;450&quot; height=&quot;315&quot; src=&quot;https:&#x2F;&#x2F;www.youtube.com&#x2F;embed&#x2F;r-GiDprUTt8&quot; allowfullscreen&gt;&lt;&#x2F;iframe&gt; &lt;figcaption&gt;Microphone output test&lt;&#x2F;figcaption&gt;
&lt;p&gt;Part A of this lab is mainly to set up and test if the microcontroller functions properly with the computer, which it does.&lt;&#x2F;p&gt;
&lt;h2 id=&quot;lab-1b&quot;&gt;Lab 1B&lt;&#x2F;h2&gt;
&lt;h3 id=&quot;introduction&quot;&gt;Introduction&lt;&#x2F;h3&gt;
&lt;p&gt;With regards to the prelab and background reading, this is what I understand:&lt;&#x2F;p&gt;
&lt;p&gt;Bluetooth Low Energy (BLE) enables a lightweight communication link between my computer and the Artemis board. At a high level:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;The Artemis acts as a BLE peripheral that advertises a service (UUID).&lt;&#x2F;li&gt;
&lt;li&gt;The computer acts as the BLE central, connects to the advertised service, and interacts with characteristics.&lt;&#x2F;li&gt;
&lt;li&gt;Characteristics support operations like Read, Write, and Notify. In this lab, I used Write to send commands to the Artemis and Notify to stream messages back to the laptop.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;The code provided to me supports, including but not limited to, the following functionality:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;ble_arduino.ino: Arduino sketch running on the Artemis (defines service + RX&#x2F;TX characteristics and command handling).&lt;&#x2F;li&gt;
&lt;li&gt;RobotCommand.h: parses incoming command strings of the form &lt;code&gt;&amp;lt;cmd_type&amp;gt;:&amp;lt;value1&amp;gt;|&amp;lt;value2&amp;gt;|...&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;EString.h: safely constructs outgoing strings (including float formatting) without relying on printf float support.&lt;&#x2F;li&gt;
&lt;li&gt;demo.ipynb: Python&#x2F;Jupyter notebook used to connect, send commands, and receive notifications.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;Useful functions:&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;&lt;code&gt;ble.connect() &#x2F; ble.disconnect()&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;&lt;code&gt;ble.send_command(cmd_type, data)&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;&lt;code&gt;ble.start_notify(uuid, handler)&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;&lt;code&gt;ble.bytearray_to_string(byteArray)&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;h3 id=&quot;setup&quot;&gt;Setup&lt;&#x2F;h3&gt;
&lt;ol&gt;
&lt;li&gt;Installed virtual environment tooling: &lt;code&gt;python3 -m pip install --user virtualenv&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;Created venv: &lt;code&gt;python3 -m venv FastRobots_ble&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;Activated: &lt;code&gt;source FastRobots_ble&#x2F;bin&#x2F;activate&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;Installed packages: &lt;code&gt;pip install numpy pyyaml colorama nest_asyncio bleak jupyterlab&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;Started JupyterLab: &lt;code&gt;jupyter lab&lt;&#x2F;code&gt;&lt;&#x2F;li&gt;
&lt;li&gt;After running &lt;code&gt;uuid4()&lt;&#x2F;code&gt;, I updated connections.yaml with my Artemis MAC address (from the Serial Monitor) and a unique BLE service UUID.&lt;&#x2F;li&gt;
&lt;&#x2F;ol&gt;
&lt;figure&gt;
&lt;img src=&quot;mac_address.JPG&quot; alt=&quot;MAC address&quot; style=&quot;display:block;&quot;&gt;
&lt;figcaption&gt;Artemis MAC address output&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;figure&gt;
&lt;img src=&quot;connection_yaml.JPG&quot; alt=&quot;connections.yaml&quot; style=&quot;display:block;&quot;&gt;
&lt;figcaption&gt;Updated connections.yaml (service UUID + MAC)&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;ol start=&quot;7&quot;&gt;
&lt;li&gt;Connected successfully to the Artemis Nano board in Python:&lt;&#x2F;li&gt;
&lt;&#x2F;ol&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; get_ble_controller()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.connect()&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;success_connection.JPG&quot; alt=&quot;BLE connect&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;Successful BLE connection&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-1&quot;&gt;TASK 1&lt;&#x2F;h4&gt;
&lt;p&gt;I sent a string from my computer using ECHO. The Artemis constructed an augmented reply and transmitted it back over the TX string characteristic.&lt;&#x2F;p&gt;
&lt;p&gt;Artemis:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;&#x2F;*&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    * Add a prefix and postfix to the string value extracted from the command string&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    *&#x2F;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; ECHO:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; TASK 1 &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    char&lt;&#x2F;span&gt;&lt;span&gt; char_arr[MAX_MSG_SIZE];&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Extract the next value from the command string as a character array&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(char_arr);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clear&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Robot says -&amp;gt; &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(char_arr);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot; :)&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_characteristic_string.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;writeValue&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;println&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Python:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# TASK 1: Send an ECHO command with the string &amp;quot;Hello World!&amp;quot;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;ECHO&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;Hello World!&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# Receive the echoed string from the RX_STRING characteristic and print it&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;echoed_string&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; ble.receive_string(ble.uuid[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;RX_STRING&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(echoed_string)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;echo.JPG&quot; alt=&quot;ECHO output&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;ECHO output received on laptop&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-2&quot;&gt;TASK 2&lt;&#x2F;h4&gt;
&lt;p&gt;I sent three floats with SEND_THREE_FLOATS and extracted them on the Artemis.&lt;&#x2F;p&gt;
&lt;p&gt;Artemis:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; SEND_THREE_FLOATS:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; TASK 2&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    float&lt;&#x2F;span&gt;&lt;span&gt; float_c, float_d, float_e;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Extract the next value from the command string as a float&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(float_c);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Extract the next value from the command string as a float&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(float_d);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Extract the next value from the command string as a float&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(float_e);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Three Floats: &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(float_c);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;, &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(float_d);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;, &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    Serial.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;println&lt;&#x2F;span&gt;&lt;span&gt;(float_e);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;Python:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# TASK 2 : Send a command to send 3 floats to the Artemis&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;SEND_THREE_FLOATS&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;11.0|-12.3|0.01&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;three_float.JPG&quot; alt=&quot;Three floats output&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;SEND_THREE_FLOATS serial output&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-3&quot;&gt;TASK 3&lt;&#x2F;h4&gt;
&lt;p&gt;I added &lt;code&gt;GET_TIME_MILLIS&lt;&#x2F;code&gt;, which replies with a timestamp string formatted as &lt;code&gt;T:&amp;lt;millis&amp;gt;&lt;&#x2F;code&gt;. The results of this task are shown in Task 4. I also had to add &lt;code&gt;GET_TIME_MILLIS&lt;&#x2F;code&gt; to &lt;code&gt;cmd_types.py&lt;&#x2F;code&gt; in the right order within the types file.&lt;&#x2F;p&gt;
&lt;p&gt;Artemis:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;&#x2F;*&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    * Reply with the timestamp in a string&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    *&#x2F;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; GET_TIME_MILLIS: {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; TASK 3&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    unsigned long&lt;&#x2F;span&gt;&lt;span&gt; now &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; millis&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clear&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    char&lt;&#x2F;span&gt;&lt;span&gt; buf[MAX_MSG_SIZE];&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;    snprintf&lt;&#x2F;span&gt;&lt;span&gt;(buf,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; sizeof&lt;&#x2F;span&gt;&lt;span&gt;(buf),&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;T:&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;%lu&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;, now);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(buf);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    tx_characteristic_string.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;writeValue&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Serial.println(tx_estring_value.c_str());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;h4 id=&quot;task-4&quot;&gt;TASK 4&lt;&#x2F;h4&gt;
&lt;p&gt;I set up a minimal notification handler in Python to receive strings from the Artemis via BLE notifications.&lt;&#x2F;p&gt;
&lt;p&gt;Python:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# TASK 4: Create a notification handler&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;def&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; make_notification_handler&lt;&#x2F;span&gt;&lt;span&gt;(controller):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    def&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; handler&lt;&#x2F;span&gt;&lt;span&gt;(sender:&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; int&lt;&#x2F;span&gt;&lt;span&gt;, byte_array:&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; bytearray&lt;&#x2F;span&gt;&lt;span&gt;):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        try&lt;&#x2F;span&gt;&lt;span&gt;:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            msg&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; controller.bytearray_to_string(byte_array)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;            print&lt;&#x2F;span&gt;&lt;span&gt;(msg)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        except&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; Exception&lt;&#x2F;span&gt;&lt;span&gt;:&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            msg&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; bytes&lt;&#x2F;span&gt;&lt;span&gt;(byte_array).decode(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #E36209;&quot;&gt;errors&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;ignore&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        # Strip common C-string padding&#x2F;line endings&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        msg&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; msg.strip(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;\x00\r\n&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    return&lt;&#x2F;span&gt;&lt;span&gt; handler&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# TASK 4: Test the notification handler by registering it and reading timestamps&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;handler&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span&gt; make_notification_handler(ble)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# ble.stop_notify(ble.uuid[&amp;#39;RX_STRING&amp;#39;])&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.start_notify(ble.uuid[&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;#39;RX_STRING&amp;#39;&lt;&#x2F;span&gt;&lt;span&gt;], handler)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;print&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;Listening for notifications&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;GET_TIME_MILLIS&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;) &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;notification.JPG&quot; alt=&quot;Notification output&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;Notification handler receiving Artemis strings&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-5&quot;&gt;TASK 5&lt;&#x2F;h4&gt;
&lt;p&gt;I ran a short for loop sending 50 &lt;code&gt;GET_TIME_MILLIS&lt;&#x2F;code&gt; repeatedly and used the timestamps received to estimate throughput. I wrote the for loop in the Jupyter notebook; equivalently, it is talking to the Artemis board 50 times via BLE.&lt;&#x2F;p&gt;
&lt;p&gt;Python:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;python&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;# TASK 5: Make a loop to send the GET_TIME_MILLIS command 50 times and process it using the notification handler&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;for&lt;&#x2F;span&gt;&lt;span&gt; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; in&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; range&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;50&lt;&#x2F;span&gt;&lt;span&gt;):&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    ble.send_command(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;CMD&lt;&#x2F;span&gt;&lt;span&gt;.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;GET_TIME_MILLIS&lt;&#x2F;span&gt;&lt;span&gt;,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;)&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;
&lt;p&gt;From the printed timestamps, the average inter-message gap was approximately 58.66 ms, corresponding to 17.05 messages&#x2F;sec. Each message being 9 characters long means its payload is about 9 bytes (1 byte per character), giving an effective payload throughput of approximately:&lt;&#x2F;p&gt;
&lt;p&gt;data rate ≈ (messages&#x2F;sec) × (bytes&#x2F;message) = 153.43 bytes&#x2F;sec&lt;&#x2F;p&gt;
&lt;figure&gt;
&lt;img src=&quot;get_time_millis.JPG&quot; alt=&quot;Task 5 output&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;GET_TIME_MILLIS loop output&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-6&quot;&gt;TASK 6&lt;&#x2F;h4&gt;
&lt;p&gt;I implemented an Arduino timestamp buffer (global array) of size 500 (arbitrary) and added &lt;code&gt;SEND_TIME_DATA&lt;&#x2F;code&gt; to send stored timestamps back to the laptop. You can request it for any integer number of times. It first stores the timestamps in the buffer by running &lt;code&gt;millis()&lt;&#x2F;code&gt; the requested number of times. Then it publishes the buffer results one by one to my computer. I added additional logic for handling the buffer overflow, which sends all the data once the buffer is full, then clears it and restarts the timestamp collection. This method balances the reliability of the data and the availability of data. Again, I had to add &lt;code&gt;SEND_TIME_DATA&lt;&#x2F;code&gt; to &lt;code&gt;cmd_types.py&lt;&#x2F;code&gt; in the right order within the types file.&lt;&#x2F;p&gt;
&lt;ul&gt;
&lt;li&gt;Advantage: Sampling happens locally without waiting for BLE round-trips.&lt;&#x2F;li&gt;
&lt;li&gt;Implementation: Store up to capacity, then transmit and restart.&lt;&#x2F;li&gt;
&lt;&#x2F;ul&gt;
&lt;p&gt;Artemis:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;&#x2F;*&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    * SEND_TIME_DATA: Iterate over the stored timestamps and send each as a string&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    *&#x2F;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; SEND_TIME_DATA:{&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; TASK 6 &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;* Serial.print(&amp;quot;Sending &amp;quot;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    Serial.println(&amp;quot; timestamps...&amp;quot;); *&#x2F;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Total number of timestamps wanted&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    int&lt;&#x2F;span&gt;&lt;span&gt; interval;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Extract the next value from the command string as an int&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(interval);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    int&lt;&#x2F;span&gt;&lt;span&gt; remaining &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; interval;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    while&lt;&#x2F;span&gt;&lt;span&gt; (remaining &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; Number to sample in this chunk&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        int&lt;&#x2F;span&gt;&lt;span&gt; n &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; remaining;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        if&lt;&#x2F;span&gt;&lt;span&gt; (n &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; TS_CAPACITY) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            n &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; TS_CAPACITY;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; Fill buffer&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        for&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; n; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            timestamps[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; millis&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; Send this chunk&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        for&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; n; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clear&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;            char&lt;&#x2F;span&gt;&lt;span&gt; ts_buf[MAX_MSG_SIZE];&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;            snprintf&lt;&#x2F;span&gt;&lt;span&gt;(ts_buf,&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; sizeof&lt;&#x2F;span&gt;&lt;span&gt;(ts_buf),&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt; &amp;quot;T:&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt;%lu&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;, timestamps[i]);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(ts_buf);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_characteristic_string.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;writeValue&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        remaining &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-=&lt;&#x2F;span&gt;&lt;span&gt; n;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;send_time_data.JPG&quot; alt=&quot;SEND_TIME_DATA&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;SEND_TIME_DATA output&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-7&quot;&gt;TASK 7&lt;&#x2F;h4&gt;
&lt;p&gt;I added a second buffer array for temperature values (same length as timestamps = 500). Both are global arrays. Each index corresponds to a paired measurement. &lt;code&gt;GET_TEMP_READINGS&lt;&#x2F;code&gt; sends &lt;code&gt;T:&amp;lt;ms&amp;gt; , TEMP:&amp;lt;val&amp;gt;&lt;&#x2F;code&gt; on each line. It allows the users to request the number of times they want to get the data, and it fetches the current time and temp sequentially, ensuring their values are synchronized. The publishing and buffer overflow logic is handled just like TASK 6. Again, I had to add &lt;code&gt;GET_TEMP_READINGS&lt;&#x2F;code&gt; to &lt;code&gt;cmd_types.py&lt;&#x2F;code&gt; in the right order within the types file.&lt;&#x2F;p&gt;
&lt;p&gt;Artemis:&lt;&#x2F;p&gt;
&lt;pre class=&quot;giallo&quot; style=&quot;color: #24292E; background-color: #FFFFFF;&quot;&gt;&lt;code data-lang=&quot;cpp&quot;&gt;&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;&#x2F;*&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    * GET_TEMP_READINGS: Send paired timestamp and temperature readings&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    *&#x2F;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;case&lt;&#x2F;span&gt;&lt;span&gt; GET_TEMP_READINGS: {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; TASK 7&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    &lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Total number of timestamp and temp readings wanted&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    int&lt;&#x2F;span&gt;&lt;span&gt; interval;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;    &#x2F;&#x2F; Extract the next value from the command string as an int&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    success &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; robot_cmd.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;get_next_value&lt;&#x2F;span&gt;&lt;span&gt;(interval);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    if&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;!&lt;&#x2F;span&gt;&lt;span&gt;success)&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; return&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    int&lt;&#x2F;span&gt;&lt;span&gt; remaining &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; interval;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    while&lt;&#x2F;span&gt;&lt;span&gt; (remaining &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; Number to sample in this chunk&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        int&lt;&#x2F;span&gt;&lt;span&gt; n &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; remaining;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        if&lt;&#x2F;span&gt;&lt;span&gt; (n &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;gt;&lt;&#x2F;span&gt;&lt;span&gt; TS_CAPACITY) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            n &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span&gt; TS_CAPACITY;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; Fill buffer&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        for&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; n; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            timestamps[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; millis&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tempreads[i]&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt; =&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt; getTempDegF&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #6A737D;&quot;&gt;        &#x2F;&#x2F; Send this chunk&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;        for&lt;&#x2F;span&gt;&lt;span&gt; (&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;int&lt;&#x2F;span&gt;&lt;span&gt; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;=&lt;&#x2F;span&gt;&lt;span style=&quot;color: #005CC5;&quot;&gt; 0&lt;&#x2F;span&gt;&lt;span&gt;; i &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;&amp;lt;&lt;&#x2F;span&gt;&lt;span&gt; n; i&lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;++&lt;&#x2F;span&gt;&lt;span&gt;) {&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;clear&lt;&#x2F;span&gt;&lt;span&gt;();&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot;T:&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(timestamps[i]);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(&lt;&#x2F;span&gt;&lt;span style=&quot;color: #032F62;&quot;&gt;&amp;quot; , TEMP:&amp;quot;&lt;&#x2F;span&gt;&lt;span&gt;);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;append&lt;&#x2F;span&gt;&lt;span&gt;(tempreads[i]);&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;            tx_characteristic_string.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;writeValue&lt;&#x2F;span&gt;&lt;span&gt;(tx_estring_value.&lt;&#x2F;span&gt;&lt;span style=&quot;color: #6F42C1;&quot;&gt;c_str&lt;&#x2F;span&gt;&lt;span&gt;());&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;        remaining &lt;&#x2F;span&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;-=&lt;&#x2F;span&gt;&lt;span&gt; n;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;    }&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span style=&quot;color: #D73A49;&quot;&gt;    break&lt;&#x2F;span&gt;&lt;span&gt;;&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;span&gt;}&lt;&#x2F;span&gt;&lt;&#x2F;span&gt;
&lt;span class=&quot;giallo-l&quot;&gt;&lt;&#x2F;span&gt;&lt;&#x2F;code&gt;&lt;&#x2F;pre&gt;&lt;figure&gt;
&lt;img src=&quot;get_temp_data.JPG&quot; alt=&quot;Temp readings&quot; style=&quot;display:block;&quot;&gt; &lt;figcaption&gt;Timestamp + temperature streaming&lt;&#x2F;figcaption&gt;
&lt;&#x2F;figure&gt;
&lt;h4 id=&quot;task-8&quot;&gt;TASK 8&lt;&#x2F;h4&gt;
&lt;p&gt;Method 1 (Task 5) fetches and sends the data one at a time. It is definitely slower for recording because each sample depends on BLE command&#x2F;response timing, wasting a lot of time sending and receiving communication. It is, however, useful for simple debugging and low-rate telemetry when real-time interaction matters. Especially, if we decided to have a really large buffer, the data might be stale by the time you get it on the computer side.&lt;&#x2F;p&gt;
&lt;p&gt;Method 2 (Tasks 6–7) fetches in volume and sends one at a time. It records data faster because the sampling is local; BLE is only used afterward to transmit stored results. This is ideal for burst logging and experiments where high-rate sampling matters more than immediate real-time feedback. The downside is the delayed availability of the data on the laptop, as I mentioned, and transmission can still be limited by notification throughput.&lt;&#x2F;p&gt;
&lt;p&gt;How quickly can Method 2 record data?
It is primarily limited by the sensor read and loop overhead on the Artemis. In my test sending 400 requests for &lt;code&gt;SEND_TIME_DATA&lt;&#x2F;code&gt;, recording 400 samples took approximately 13 ms, or roughly 0.03 ms&#x2F;sample, which is almost 2000 times faster.&lt;&#x2F;p&gt;
&lt;p&gt;Memory estimate (384 kB RAM):
Each timestamp is 4 bytes (int), and each temp is 4 bytes (float) → 8 bytes per paired sample. Including the global variables I have, which take up 34,152 bytes, but ignoring other overhead, the theoretical upper bound is approximately:&lt;&#x2F;p&gt;
&lt;p&gt;349,848 bytes &#x2F; 8 ≈ 43,731 sample pairs could potentially be stored in the array before the board runs out of dynamic memory.
A more realistic, safe capacity is lower, depending on current global&#x2F;static memory usage reported by the Arduino IDE.&lt;&#x2F;p&gt;
&lt;h3 id=&quot;discussion-and-conclusion&quot;&gt;Discussion and Conclusion&lt;&#x2F;h3&gt;
&lt;ol&gt;
&lt;li&gt;I learned how BLE services&#x2F;characteristics map to read&#x2F;write&#x2F;notify behavior and how the Artemis acts as a peripheral device. I also learned to write commands to control the Artemis board using lower-level libraries like &lt;code&gt;RobotCommand.h&lt;&#x2F;code&gt;. Finally, I learned about the limits on how fast the Artemis&#x27;s temperature sensor can be polled, which is really fast.&lt;&#x2F;li&gt;
&lt;li&gt;I implemented an interesting way of handling the buffer overflow for TASKS 6-7, balancing between the availability of data and the reliability of data.&lt;&#x2F;li&gt;
&lt;li&gt;The main debugging challenge was making sure that the environment was set up to run the Jupyter notebook. I spent way too long on it when it was just an easy fix. But now I really remember it. Also, I thought about perhaps sending the buffer information in one message, which would depend on how long I could make an EString. Theoretically, I can make it 255 bytes with the Arduino BLE limit, which for TASKS 5-6, is 20-30 messages depending on the length of the timestamp. Realistically, it would not impact the reliability of the data, because the data is already recorded in the buffer, but it can decrease the delay in the delivery of the data.&lt;&#x2F;li&gt;
&lt;&#x2F;ol&gt;
&lt;h3 id=&quot;collaboration&quot;&gt;Collaboration&lt;&#x2F;h3&gt;
&lt;p&gt;I collaborated with: Ananya Jajodia.&lt;&#x2F;p&gt;
&lt;p&gt;I referenced: Lucca Correia&#x27;s site for web design and lab writeup.&lt;&#x2F;p&gt;
&lt;p&gt;ChatGPT was used for: code debugging + website formatting.&lt;&#x2F;p&gt;
</description>
      </item>
    </channel>
</rss>
