tag:blogger.com,1999:blog-17590465127921025532024-03-28T22:19:13.247-07:00Building and CrashingA journal of my exploits in building things and then frequently crashing them. Mostly centered around multirotors and UAVs but really whatever strikes my fancy to build.
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.comBlogger58125tag:blogger.com,1999:blog-1759046512792102553.post-28398887407144491922017-03-12T12:17:00.001-07:002017-03-12T12:17:44.058-07:00EMG Chase Game<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
I dusted off <a href="http://buildandcrash.blogspot.com/2014/01/eeg-stuffing-and-testing.html">SparkyEEG</a> recently and used it for some fun with EMG processing, as well as an excuse to do some learning with <a href="http://tensorflow.org/">TensorFlow</a> and deep learning (as an aside I read the <a href="http://www.deeplearningbook.org/">Deep Learning Book</a> by Goodfellow et al. and really enjoyed it). I placed the 8 electrodes across various muscles, mostly around shoulders.<br />
<br />
I'm using some fairly simple (and common) preprocessing on the raw electrophysiology data to first get the EMG power. This applies a bandpass filter, rectification, and then measures the "waveform length" which is the integral of the absolute value of the difference.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5g0L4GvJ3VBwapPGt99Mb1Q0f1aHMDIPhb0RJvwnsqppH9Zalw7gvEoYWFCqhTjkNZy3p84VWD60z_p8BgGpXpu2wKQvZ7pdmGr7DlP_tp5yP2fxvHm7gkz8Z0wgGeNm2dG6AOVHbONM/s1600/L_deltoid.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="192" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5g0L4GvJ3VBwapPGt99Mb1Q0f1aHMDIPhb0RJvwnsqppH9Zalw7gvEoYWFCqhTjkNZy3p84VWD60z_p8BgGpXpu2wKQvZ7pdmGr7DlP_tp5yP2fxvHm7gkz8Z0wgGeNm2dG6AOVHbONM/s320/L_deltoid.png" width="320" /></a></div>
<br />
<h3 style="text-align: left;">
Representation learning</h3>
First I wrote up an autoencoder (and then a variational autoencoder) to take some EMG data and perform unsupervised dimensionality reduction. It also helps denoise the data and remove things like EKG contamination.<br />
<br />
<blockquote class="instagram-media" data-instgrm-captioned="" data-instgrm-version="7" style="background: #fff; border-radius: 3px; border: 0; box-shadow: 0 0 1px 0 rgba(0 , 0 , 0 , 0.5) , 0 1px 10px 0 rgba(0 , 0 , 0 , 0.15); margin: 1px; max-width: 350px; padding: 0; width: 99.375%;">
<div style="padding: 8px;">
<div style="background: #F8F8F8; line-height: 0; margin-top: 40px; padding: 50.0% 0; text-align: center; width: 100%;">
<div style="background: url(data:image/png; display: block; height: 44px; margin: 0 auto -44px; position: relative; top: -22px; width: 44px;">
</div>
</div>
<div style="margin: 8px 0 0 0; padding: 0 4px;">
<a href="https://www.instagram.com/p/BQ_Ff9GFX0j/" style="color: black; font-family: "arial" , sans-serif; font-size: 14px; font-style: normal; font-weight: normal; line-height: 17px; text-decoration: none; word-wrap: break-word;" target="_blank">Fun times with #sparkyeeg and #tensorflow to train an autoencoders in real-time on my muscle activity. It ends up (this run) learning some pretty natural movements.</a></div>
</div>
</blockquote>
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script>
<br />
<br />
And here are some graphs of the latent variables learned<br />
<br />
<div style="text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhqkDwvbqYon_6vTiafZowUJqB7JJMdlvQwNAsFHmkwUxspeKTdeFIcR4RMBDHNISpO2uP-a5DI54pqgdJX3v3GGLVv_XBtPFjxIJWE91aOt80nRKJLToiiN24ZoX1lWaZB_v0jPwsfwOk/s1600/autoencoder.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="191" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhqkDwvbqYon_6vTiafZowUJqB7JJMdlvQwNAsFHmkwUxspeKTdeFIcR4RMBDHNISpO2uP-a5DI54pqgdJX3v3GGLVv_XBtPFjxIJWE91aOt80nRKJLToiiN24ZoX1lWaZB_v0jPwsfwOk/s400/autoencoder.png" width="400" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="text-align: left;">
Arm movement tracking</h3>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">Then I used my kinect to record my arm positions while recording EMG data in parallel. I used the a neural network to predict my arm positions based upon the EMG data.</span></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<blockquote class="instagram-media" data-instgrm-captioned="" data-instgrm-version="7" style="background: #fff; border-radius: 3px; border: 0; box-shadow: 0 0 1px 0 rgba(0 , 0 , 0 , 0.5) , 0 1px 10px 0 rgba(0 , 0 , 0 , 0.15); margin: 1px; max-width: 350px; padding: 0; width: 99.375%;">
<div style="padding: 8px;">
<div style="background: #F8F8F8; line-height: 0; margin-top: 40px; padding: 50.0% 0; text-align: center; width: 100%;">
<div style="background: url(data:image/png; display: block; height: 44px; margin: 0 auto -44px; position: relative; top: -22px; width: 44px;">
</div>
</div>
<div style="margin: 8px 0 0 0; padding: 0 4px;">
<a href="https://www.instagram.com/p/BQ_GFtglvUb/" style="color: black; font-family: "arial" , sans-serif; font-size: 14px; font-style: normal; font-weight: normal; line-height: 17px; text-decoration: none; word-wrap: break-word;" target="_blank">Recording movements and joint positions with a Kinect to correlate with EMG activity. Soon... arm controlled quad?</a></div>
</div>
</blockquote>
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script>
<span style="text-align: left;"><br /></span><br />
And again here is a graph of the reconstruction (the data after 150s is held back test data), sorry for the time shift.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgS95R34JPhDdJdWIchvp4V6vI_4hjQA6I87kFEuHARJ1R1SPTRSkc7AoH5jIjIPAi6AR6kWEPbXkLHf2d_xAJ8-VawOg4tpAn188LJJ-99_peI4KZWs-xIzNeDeK3vJgVT55lCfjP_8xI/s1600/position_reconstruction.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="241" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgS95R34JPhDdJdWIchvp4V6vI_4hjQA6I87kFEuHARJ1R1SPTRSkc7AoH5jIjIPAi6AR6kWEPbXkLHf2d_xAJ8-VawOg4tpAn188LJJ-99_peI4KZWs-xIzNeDeK3vJgVT55lCfjP_8xI/s400/position_reconstruction.png" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="text-align: left;">
<span style="text-align: left;">Game</span></h3>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">Then sort of putting this all together I wrote a game to chase a maker using EMG activity. The way this works is first prelearning a representation using a variational autoencoder as I sit and move my arms around. These graphs are from the tensor board that shows the log likelihood of the data improving and the Kullback-Liebler divergence of the latent space increases (the total lower bound does continue to increase). I should probably run it for longer as it hasn't stabilized, but it gets a bit boring :).</span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;"><br /></span></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg6FbId-fr6OlD2hdicx4LWtKDQmPBkgyNrTtOmS3IJ2OWIDSQbJ0O94uJvA-DcQ2IkNdYovmWuMqOAD1WbxMJX06aFb4I34Y8qyTS-mfN2Lau4NGimxIxGjiHcP_gaauT2VLWxiBm-WSw/s1600/Screen+Shot+2017-03-12+at+1.42.37+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="126" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg6FbId-fr6OlD2hdicx4LWtKDQmPBkgyNrTtOmS3IJ2OWIDSQbJ0O94uJvA-DcQ2IkNdYovmWuMqOAD1WbxMJX06aFb4I34Y8qyTS-mfN2Lau4NGimxIxGjiHcP_gaauT2VLWxiBm-WSw/s400/Screen+Shot+2017-03-12+at+1.42.37+PM.png" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<br />
<div class="separator" style="clear: both; text-align: left;">
Then I start playing a game which adds a linear network to the output of the latent space to try and predict the X and Y positions of the cursor. Here you can see the mean squared prediction error improves while playing the game and then stabilizes after a while. The residual noise appears to be mostly high frequency noise. The learning function initially learns just the output network but then after enough time to initialize that can back-propagate through the representation layer to try and improve the representation.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEigYzosJ3BkmQDEPsCzdxw8Q_gsTQ6X2NpCvbn9ogyymdoNfsUn8RqYyyTUwnyFp7Utb5kD06SW-mpT8BZlTpy3R0ZFIn3le5g9cT8WkAfp5aHb9d6UPMQxrBf214yw_EAgv5hl0GPl6V8/s1600/Screen+Shot+2017-03-12+at+12.01.45+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="243" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEigYzosJ3BkmQDEPsCzdxw8Q_gsTQ6X2NpCvbn9ogyymdoNfsUn8RqYyyTUwnyFp7Utb5kD06SW-mpT8BZlTpy3R0ZFIn3le5g9cT8WkAfp5aHb9d6UPMQxrBf214yw_EAgv5hl0GPl6V8/s320/Screen+Shot+2017-03-12+at+12.01.45+PM.png" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">Here is a video of me playing this game and how well it does. Not perfect but not bad for a first implementation I wrote up an autoencoder (and then a variational autoencoder) to take some EMG data and perform unsupervised dimensionality reduction. It also helps denoise the data and remove things like EKG contamination.</span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;"><br /></span></div>
<blockquote class="instagram-media" data-instgrm-captioned="" data-instgrm-version="7" style="background: #fff; border-radius: 3px; border: 0; box-shadow: 0 0 1px 0 rgba(0 , 0 , 0 , 0.5) , 0 1px 10px 0 rgba(0 , 0 , 0 , 0.15); margin: 1px; max-width: 350px; padding: 0; text-align: center; width: 99.375%;">
<div style="padding: 8px;">
<div style="background: #F8F8F8; line-height: 0; margin-top: 40px; padding: 29.583333333333332% 0; text-align: center; width: 100%;">
<div style="background: url(data:image/png; display: block; height: 44px; margin: 0 auto -44px; position: relative; top: -22px; width: 44px;">
</div>
</div>
<div style="margin: 8px 0 0 0; padding: 0 4px; text-align: center;">
<a href="https://www.instagram.com/p/BRjI4NUllhR/" style="color: black; font-family: "arial" , sans-serif; font-size: 14px; font-style: normal; font-weight: normal; line-height: 17px; text-decoration: none; word-wrap: break-word;" target="_blank">More fun with #sparkyeeg and #tensorflow to try and make a neural network learn to map from EMG to cursor position. Long way to go but I'm pleased for a first pass.</a></div>
</div>
</blockquote>
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script>
<br />
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">While playing it's basically co-learning with the user, as you pick some movements to try and control the cursor and keep sticking with it, and it tries to map from those movements to the cursor position. It will take some exploring to figure out the right dynamics to try and let it optimally bootstrap this system. For example:</span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;"><br /></span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">1. picking the set of cursor position where the decoder is most uncertain</span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">2. how long should the memory buffer be to stabilize the system versus to allow it to evolve</span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;">3. how should the learning rate of the network adapt with time.</span></div>
<div class="separator" style="clear: both; text-align: left;">
<span style="text-align: left;"><br /></span></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com69tag:blogger.com,1999:blog-1759046512792102553.post-66506382614329543312016-10-30T17:28:00.002-07:002016-10-30T17:43:25.818-07:00Linear Gaussian Quadratic Control System<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div dir="ltr" style="text-align: left;" trbidi="on">
For the last year when I've had time, I have been developing an entirely new control scheme (at least as far as I know for the open source community) for multi rotors that replaces PID by expanding upon <a href="https://vimeo.com/104806460">Tau Labs System Identification</a> (see the mathematical description <a href="https://github.com/TauLabs/TauLabs/raw/next/flight/Doc/Autotuning%20Derivation.pdf">here</a>).<br />
<br />
The way linear quadratic control (LQG) works is by simultaneously estimating additional properties in the system we cannot directly measure (in this case the instantaneous torque and true rate of rotation) and the using those to control the system. I had previously experimented with something a bit ad hoc <a href="https://vimeo.com/59860771">like this in the past</a>.<br />
<h2 style="text-align: left;">
</h2>
<h2 style="text-align: left;">
</h2>
<h2 style="text-align: left;">
<br /></h2>
<h2 style="text-align: left;">
System Identification</h2>
<br />
A while ago Korken <a href="http://forum.taulabs.org/viewtopic.php?f=17&t=99&start=10#p965">proposed a nice EKF</a> that would extract a few critical properties of the system (primarily the 'gain' of each axis and the time constant of the motors). I wrote up an implementation of this and we got it running and measuring reasonable values. Based on this, I came up with some <a href="https://github.com/TauLabs/TauLabs/raw/next/flight/Doc/Autotuning%20Derivation.pdf">analytic approaches</a> to optimize the PID control parameters based on these estimated system properties.<br />
<br />
More specifically we use a model with several parameters that are specific to each frame $\beta_1$, $\beta_2$, $\tau$. The latency of the ESC/Motor/Prop is captured by $\tau$ and is one of the most performance limiting factors in a frame. For roll and pitch only $\beta_1$ is used and corresponds to the strength of that control output. For yaw there is a component that has no latency -- $\beta_2$ -- and that corresponds to directly generating a reaction force torque by accelerating the props.<br />
<br />
$\dot \theta = \omega$<br />
$\dot \omega = \beta_1 \cdot \nu + \beta_2 \cdot \left(u_c - \nu \right)$<br />
$\dot \nu = \frac{u_c - \nu}{\tau}$<br />
<br />
The EKF above will estimate these parameters for a frame by having it <a href="https://vimeo.com/104806460">shake while flying</a>.<br />
<h2 style="text-align: left;">
</h2>
<h2 style="text-align: left;">
</h2>
<h2 style="text-align: left;">
<br /></h2>
<h2 style="text-align: left;">
Online estimation</h2>
<br />
To perform linear quadratic control (LQR) we need to be able to estimate $\nu$ which is the instantaneous (normalized) torque on the frame. In addition, we would like to estimate $\omega$ -- the true rotation rate -- although we have the noisy measured values of it from gyro.<br />
<br />
We can take the above system dynamical equations and convert it to a continuous time state space representation. Because the output may be slightly biased we also need to include this into the state estimation $b$. In addition, this estimator will not estimate the angle as we will take that from either the complementary filter or the INS.<br />
<br />
$\mathbf x = \left( \begin{matrix} \omega \\ \nu \\ b \end{matrix} \right)$<br />
<br />
We can the write down the equations above (including bias) as<br />
<br />
$\dot {\mathbf x} = \mathbf A_c \mathbf x + \mathbf b u + \mathbf w$<br />
<br />
$\mathbf A_c = \left( \begin{matrix}<br />
0 & \beta_1-\beta_2 & -\beta_2 \\<br />
0 & -1/\tau & -1/\tau \\<br />
0 & 0 & 0<br />
\end{matrix} \right)$<br />
<br />
$\mathbf b_c = \left( \begin{matrix}<br />
\beta_2 \\<br />
1/\tau \\<br />
0<br />
\end{matrix} \right)$<br />
<br />
Of course since we are going to be implementing this in discrete time, we need to convert from the continuous time representation.<br />
<br />
$\mathbf x_{t+1} = \mathbf A_d \mathbf x_t + \mathbf b_d u_t + \mathbf{w}_d$<br />
<br />
$\mathbf A_d = e^{\mathbf A_c T_s}<br />
= \left( \begin{matrix}<br />
1 & A_{d12} & A_{d13} \\<br />
0 & e^{-T_s/\tau} & e^{-T_s/\tau} - 1 \\<br />
0 & 0 & 1<br />
\end{matrix} \right)$<br />
$\qquad A_{d12} = \beta_1 \tau - \beta_2 \tau - \beta_1 \tau \exp(-T_s/\tau) + \beta_2 \tau\exp(-T_s/\tau) = (\beta_1 - \beta_2) \left(\tau - \tau e^{-T_s/\tau}\right)$<br />
$\qquad A_{d13} = - T_s \beta_1 + \beta_1 \tau - \beta_2 \tau - \beta_1 \tau e^{-T_s/\tau} + \beta_2 \tau e^{-T_s/\tau} = - T_s \beta_1 + A_{d12}$<br />
<br />
$\mathbf b_d = \int_0^{T_s} e^{\mathbf A_c s} ds \, \mathbf b_c<br />
= \left( \begin{matrix}<br />
-A_{d13} \\<br />
1 - e^{-T_s/\tau} \\<br />
0<br />
\end{matrix} \right)$<br />
<br />
$\mathbf c = \left( \begin{matrix} 1 \\ 0 \\ 0 \end{matrix} \right)$<br />
<br />
Because this system is a linear time-invariant Kalman filter, the covariance matrix will converge to a constant regardless of the observations and can be used to pre-compute a kalman gain. This requires solving the discrete algebraic Ricatti equation (DARE) to estimate the steady state posterior noise distribution (details omitted). With this we get an equation for the estimator.<br />
<br />
$\hat {\mathbf x_{t+1}} = \mathbf A_d \hat{\mathbf x}_t + \mathbf b u_t + \mathbf l \left( y - \mathbf c^\mathrm{T} \hat {\mathbf x}_t \right)$<br />
<br />
$\mathbf l = \mathbf P \mathbf c \left[ \mathbf c^\mathrm{T} \mathbf P \mathbf c+ r\right]^{-1}$<br />
<br />
Which means once we have solved the DARE and for $\mathbf l$ the kalman filter only requires several multiplications and addition operations to update. When controlling attitude we use the angle estimate from the original complementary filter or INS algorithm.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgALFDh0OvBlETf4f-BFXZUxqeLq2dp4XhubQBDFESvY4QE_LFUfXL0c0JFiCHDvmytgkiid60GdxLozBGpOg_bD0wW5UgmnQpvnPEjEs0VFUhm030-6Mh-SYOBrK5pI59sNmTXCNue3E8/s1600/Screen+Shot+2016-10-02+at+5.29.22+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"></a></td></tr>
</tbody></table>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiympNuAUfsxJEDo5HCa7m8lQIctAkAYe8nq-nP8hKlCHJVWMcxIMkL7EplnQoyb7RIUDQaLmhQ8telhNvdK5rX0s_W_k7uZQjJY0y6FsP39Q8O37el2Eh6vkqztAtfTJh_eB2ri_5vDZg/s1600/Screen+Shot+2016-10-30+at+2.33.05+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="177" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiympNuAUfsxJEDo5HCa7m8lQIctAkAYe8nq-nP8hKlCHJVWMcxIMkL7EplnQoyb7RIUDQaLmhQ8telhNvdK5rX0s_W_k7uZQjJY0y6FsP39Q8O37el2Eh6vkqztAtfTJh_eB2ri_5vDZg/s400/Screen+Shot+2016-10-30+at+2.33.05+PM.png" width="400" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Online estimation running during an autotune session. The green line in the top plot shows how much the gyros are denoised by the Kalman filter. The bottom plot shows the online instantaneous torque estimation, which is used to replace the original derivative term in PID.</td></tr>
</tbody></table>
<div>
<br /></div>
<br />
<h2 style="text-align: left;">
Control algorithm</h2>
<br />
Armed with the state estimate we can use a linear quadratic regulator (instead of traditional PID) to compute the desired output. Here we talk about controlling the attitude. This controller has the form<br />
<br />
$u = -\mathbf k^\mathrm{T} \hat {\mathbf{x}} + b$<br />
<br />
Where $\mathbf k$ is optimized to minimize a cost function $J$ and $x=\left( \begin{matrix} \theta \\ \omega \\ \nu \end{matrix} \right)$.<br />
<br />
$J=\sum_{t=0}^{t=\infty}{\mathbf x_t' \mathbf Q \mathbf x_t + u_t r u_t}$ -- this uses $u$ without the bias added in.<br />
<br />
$\mathbf x = \left( \begin{matrix} \theta \\ \omega \\ \nu \end{matrix} \right)$<br />
<br />
Again converting the continuous dynamics to discrete time gives a system<br />
<br />
$\mathbf A_d = \left( \begin{matrix}<br />
1 & T_s & A_{d13} \\<br />
0 & 1 & A_{d23} \\<br />
0 & 0 & e^{-T_s/\tau}<br />
\end{matrix}<br />
\right) \\<br />
\qquad A_{d13} = \tau (\beta_1 - \beta_2) (\tau e^{-T_s/\tau} - \tau + T_s) \\<br />
\qquad A_{d23} = \tau (\beta_1 - \beta_2) (1 - e^{-T_s/\tau})$<br />
<br />
$\mathbf b_d = \left( \begin{matrix}<br />
T_s^2 \beta_1 / 2 - A_{d13} \\<br />
T_s \beta_1 - A_{d23} \\<br />
1-e^{-T_s/\tau}<br />
\end{matrix} \right) $<br />
<div>
<br /></div>
<div>
We can then plug these dynamics into DARE, as well as the parameters $\mathbf Q$ and $r$ from above to which determine performance tradeoffs. From that we can solve for $\mathbf k$.</div>
<div>
<br /></div>
<div>
$\mathbf k^\mathrm{T} = (r + \mathbf b^\mathrm{T} \mathbf P \mathbf b)^{-1} (\mathbf b^\mathrm{T} \mathbf P \mathbf A)$</div>
<div>
<br />
<h3 style="text-align: left;">
Costs</h3>
</div>
<div>
The parameters in the $\mathbf Q$ matrix ultimately determine the system performance -- how aggressively it attempts to drive the state to the setpoint (which will be discussed below). In this system we use a diagonal $Q = \mathrm{diag}(q_1 (1-s), q_2, q_3)$ which allows us to write the cost function a little bit more naturally.</div>
<div>
<br /></div>
<div>
$J=\int_{t=0}^{t=\infty}{q_1 \theta^2 + q_2 \omega^2 + q_{3} \nu ^2 + u_c^2 r \, \mathrm{d} t}$</div>
<div>
<br /></div>
<div>
This expression makes it clear that by having $q_1$ greater the system will more aggressively try and correct angular errors. By having $q_2$ greater it will also try and keep $\omega$ closer to zero when doing that, which has the effect of smoothing out the response. Similarly setting $q_3$ greater will attempt to drive the error to zero with the minimal amount of torque possible. Both of these will smooth the response out and lessen overshoot.</div>
<div>
<br /></div>
<div style="text-align: left;">
Because we are optimizing the feedback gains ($\mathbf k$) to minimize this function, we can divide out r -- or without loss of generality set it to 1 -- without changing $\mathbf k$.</div>
<div style="text-align: left;">
<br /></div>
<h3 style="text-align: left;">
Setpoints</h3>
<div>
<div>
To use LQR to control either rate or attitude (as opposed to drive both to zero) we need to redefine error from setpoint as</div>
<div>
<br /></div>
<div>
$\mathbf x_{r} = \mathbf x-\mathbf r$</div>
<div>
<br /></div>
<div>
which leads to us having a new control rule</div>
<div>
<br /></div>
<div>
$u=-\mathbf k^\mathrm{T} \mathbf x_r + b$</div>
<div>
<br /></div>
<div>
In order to have an attitude controller, we want</div>
<div>
<br /></div>
<div>
$\mathbf r_\theta = \left( \begin{matrix} \theta_r \quad 0 \quad 0 \end{matrix} \right)^\mathrm{T}$</div>
<div>
<br /></div>
<div>
In order to have a rate controller, we similarly change the setpoint reference to control the angular rate state and set the angle to zero</div>
<div>
<br /></div>
<div>
$\mathbf r_\omega = \left( \begin{matrix} 0 \quad \omega_r \quad 0 \end{matrix} \right)^\mathrm{T}$</div>
<div>
<br /></div>
<div>
and then set $q_{0,0}=0$ in order for the LQR controller to not penalize the angle not being at zero. This could be equivalently done with a two state system but would just complicate the code (and prevent doing things like smoothly transitioning from rate to attitude control, like in horizon mode).</div>
<div>
<br /></div>
<div>
<h3>
Frame invariant behavior and costs</h3>
<div>
Without getting too much into the derivation, by slightly tweaking the cost parameters so that $q_3 = \beta_1 q_4$ we can ultimately generate responses that are much more similar across frames regardless of their parameters. It will never be possible to get exactly identical performance if we are pushing frames to the limits of what they can do as some performance simply is not achievable on a more sluggish frame. </div>
</div>
<div>
<br /></div>
<div>
I simulated the closed loop response when changing parameters and using this representation of the cost and show that fairly consistent closed loop responses in rate mode would be achieved across a wide variety of frame types.</div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgbTk-A3VG-uWYo0BN2ANVbPi7RwG9VmFFIC-4kFNXitpL4TqM-Sca3kZKphyphenhyphenrxAVvf4n1kz91Bt1m2RWSFxvJ_oIShNCqyaYzZZCWH7v8ruuxZ2UizzHEP94OwkD2GFecJ9k4pDNWTGnU/s1600/b8_tau35.png" imageanchor="1" style="margin-left: auto; margin-right: auto; text-align: center;"><img border="0" height="177" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgbTk-A3VG-uWYo0BN2ANVbPi7RwG9VmFFIC-4kFNXitpL4TqM-Sca3kZKphyphenhyphenrxAVvf4n1kz91Bt1m2RWSFxvJ_oIShNCqyaYzZZCWH7v8ruuxZ2UizzHEP94OwkD2GFecJ9k4pDNWTGnU/s320/b8_tau35.png" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">The response and control output for a step response with $\beta=8$ and $\tau=-3.5$ is shown here.</td></tr>
</tbody></table>
<div>
</div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhC9lEG3G3kH3lZIi569RNnJx6ooUi4QWsev7EP2uG7Yw767kQ79j46QKnSbXrdZcV-hteZEqwJQgL2LJV-Mv1uah0hcUX_QIo33q-ZbJYKT78vsozV42pTXidj_8kgH7gzxXle1AUgGMA/s1600/beta_param.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="320" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhC9lEG3G3kH3lZIi569RNnJx6ooUi4QWsev7EP2uG7Yw767kQ79j46QKnSbXrdZcV-hteZEqwJQgL2LJV-Mv1uah0hcUX_QIo33q-ZbJYKT78vsozV42pTXidj_8kgH7gzxXle1AUgGMA/s320/beta_param.png" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">This shows a set of simulated step responses in rate mode when sweeping the $\beta_1$ parameter. Although there is a slight change in the shape, it is fairly minimal.</td></tr>
</tbody></table>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhY-KmZYaQBwtaHH-lg7VllUqxaU25S176o0g8NtOfGknuhpRlqitmff03LixTeE69wDA1DHxr00PyTItO2t4N_UnCmFzyhNnx_XoBaB2QXUMughm2KMGIqKc9iJpJ15b9djgr8Quaz2Dk/s1600/tau_param.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="320" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhY-KmZYaQBwtaHH-lg7VllUqxaU25S176o0g8NtOfGknuhpRlqitmff03LixTeE69wDA1DHxr00PyTItO2t4N_UnCmFzyhNnx_XoBaB2QXUMughm2KMGIqKc9iJpJ15b9djgr8Quaz2Dk/s320/tau_param.png" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;"><table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td class="tr-caption" style="font-size: 13px;">Similarly as we sweep $\tau$ there is also only a small change in the simulated closed loop performance.</td></tr>
</tbody></table>
</td></tr>
</tbody></table>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
<br /></div>
<div>
Having this type of invariance has the benefit that once some more serious pilots and tweakers find a set of costs that work well for them it should apply more -- both when using them on different frames and sharing them amongst other pilots.</div>
<div>
<br />
<h3>
Real world results</h3>
<div>
As usual when testing these kind of control algorithm, I threw <a href="http://buildandcrash.blogspot.com/2012/11/assembly-and-first-flight.html">Freedom</a> on a frame, which is a flight controller that has an Overo Gumstix on it that lets me log all the sensor data in the flight. I can then analyze the filter offline (as well as reprocess the data to refine things like the filter).</div>
<div>
<br /></div>
<div>
Here it is tied up to isolate one axis so I could test extremely high rotational speeds that I couldn't otherwise indoors.</div>
<div>
<br /></div>
<div>
<blockquote class="instagram-media" data-instgrm-version="7" style="background-color: white; border-bottom-left-radius: 3px; border-bottom-right-radius: 3px; border-top-left-radius: 3px; border-top-right-radius: 3px; border: 0px; box-shadow: rgba(0, 0, 0, 0.498039) 0px 0px 1px 0px, rgba(0, 0, 0, 0.14902) 0px 1px 10px 0px; margin: 1px; max-width: 658px; padding: 0px; width: 648.90625px;">
<div style="padding: 8px;">
<div style="background-color: #f8f8f8; background-position: initial initial; background-repeat: initial initial; line-height: 0; margin-top: 40px; padding: 316.453125px 0px; text-align: center; width: 632.90625px;">
<div style="height: 44px; margin: 0px auto -44px; position: relative; top: -22px; width: 44px;">
</div>
</div>
<div style="color: #c9c8cd; font-family: arial, sans-serif; font-size: 14px; line-height: 17px; margin-bottom: 0px; margin-top: 8px; overflow: hidden; padding: 8px 0px 7px; text-align: center; text-overflow: ellipsis; white-space: nowrap;">
<a href="https://www.instagram.com/p/BEsDahFlqg3/" style="color: #c9c8cd; text-decoration: none;" target="_blank">A video posted by peabody124 (@peabody124)</a> on <time datetime="2016-04-27T03:18:14+00:00" style="font-family: Arial,sans-serif; font-size: 14px; line-height: 17px;">Apr 26, 2016 at 8:18pm PDT</time></div>
</div>
</blockquote>
<br />
<br />
And from that I can download the logs and look at the performance when doing fast movements in attitude mode as well as in rate control.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEibp3W-1JgOLhrJeNEoQk3knrXF07RBfVJ6mht3I8ukS4aTypIgRsGkf_4skew_aZa6CPDQBbaNDEao1OtLagb8ss8WGLP6fUvPL7URsupG0oKYr3ohdLI_IpCZxWKNeXpVvopSGh_tS3w/s1600/Screen+Shot+2016-04-26+at+9.30.08+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="67" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEibp3W-1JgOLhrJeNEoQk3knrXF07RBfVJ6mht3I8ukS4aTypIgRsGkf_4skew_aZa6CPDQBbaNDEao1OtLagb8ss8WGLP6fUvPL7URsupG0oKYr3ohdLI_IpCZxWKNeXpVvopSGh_tS3w/s320/Screen+Shot+2016-04-26+at+9.30.08+PM.png" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="font-size: 13px;">Here you can see me switching between rate and attitude control. In both cases the responses are extremely crisp.</td></tr>
</tbody></table>
<div>
</div>
</div>
<br />
Here is some data from a free flying frame.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td><div style="text-align: center;">
</div>
<div style="text-align: center;">
</div>
<div style="text-align: center;">
</div>
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg9GtR7E20tOGj7IF6_JR8Vb-vQmGNZROz125x88QtPmyD1eNQOXB6OrJx6uElVcVEKnaYoIz6xO0o8rNIXnIZbHnUpBGUsImrW7j5DX7Hsk2v95HWTdItw8Hf64OkhcflFNti02wxz8gg/s1600/Screen+Shot+2016-10-30+at+2.56.02+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="235" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg9GtR7E20tOGj7IF6_JR8Vb-vQmGNZROz125x88QtPmyD1eNQOXB6OrJx6uElVcVEKnaYoIz6xO0o8rNIXnIZbHnUpBGUsImrW7j5DX7Hsk2v95HWTdItw8Hf64OkhcflFNti02wxz8gg/s400/Screen+Shot+2016-10-30+at+2.56.02+PM.png" width="400" /></a></td></tr>
<tr><td class="tr-caption" style="font-size: 13px;">The green points in the top trace show the desired angle and the blue curve is the actual angle. The system responds very promptly to the input stimuli. The bottom trace again shows the estimator that again smooths the gyro down.</td></tr>
</tbody></table>
<br />
This graph shows that the system responds very promptly. Because of the smoothed gyro and torque estimates, LQG can tolerate much greater effective gains than can work with PID control and no smoothing.<br />
<br /></div>
<h2 style="text-align: left;">
So why LQG?</h2>
<div>
After going through all this, it is worth taking a moment to ask why do we want to implement this. There are two main benefits corresponding to the two halfs of LQG. </div>
<div>
<br /></div>
<div>
The first part is the benefit of the estimation component. By running the Kalman filter we fuse together the inputs that we are sending to the motor and the noisy gyro estimates to get the best possible estimate of what is really going on. Superficially, this has the benefit of significantly denoising the gyro signal -- after all that very high frequency noise is physically implausible but applying a low pass filter to it introduces latencies that people are always trying to chase out. In addition, it allows us to directly estimate the instantanous (normalized) torque being generated by the motors. This comes from the latency of their responses and allows us to properly damp the control algorithm rather than the <i>ad hoc</i> derivative term typical in PID. The derivative is <b>critical</b> for good performance and those who have been in this game long enough to remember when the bandlimited derivative from APM was ported over to OpenPilot recall how much of a performance boom it was. However, that band limiting is required because of the amount of noise when directly taking the difference of gyro measurements. The state estimation reduces the amount of noise there allowing much greater derivative terms. <b>When looking at the parameters as the corresponding PID terms we can use much much higher PID parameters when using the state estimator. In practice I'm using a factor of 10 higher values than without this estimator.</b></div>
<div>
<b><br /></b></div>
<div>
The second half is the actual calculation of the gains. As I referenced in the beginning after we got the system identification going I came up with some analytic equations to optimize the PID coefficients from this (derivation is <a href="https://github.com/TauLabs/TauLabs/raw/next/flight/Doc/Autotuning%20Derivation.pdf">here</a>). This has worked well and feedback on Tau Labs autotuning has always been quite positive. However, LQR is a much more principled and mainstream approach to the same problem. It is more computationally intensive, but by only having to calculate the DARE equation once given the system identification parameters, we can do this before take off and avoid this cost in real time. Thus the costs of running this LQG is essentially the same as PID.<br />
<br />
<h2 style="text-align: left;">
Conclusion</h2>
LQG is a more modern control scheme than PID. It flies much better. This implementation simply requires a regular autotune flight, but instead of using the math I previously developed that is now used by TauLabs/LibrePilot/Dronin it directly computes LQR coefficients. Here I show it flying on 3 frames of much different sizes without issue:</div>
<div>
<br />
<br /></div>
</div>
</div>
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script>
</div>
<blockquote class="instagram-media" data-instgrm-captioned="" data-instgrm-version="7" style="background: #fff; border-radius: 3px; border: 0; box-shadow: 0 0 1px 0 rgba(0 , 0 , 0 , 0.5) , 0 1px 10px 0 rgba(0 , 0 , 0 , 0.15); margin: 1px; max-width: 658px; padding: 0; width: 99.375%;">
<div style="padding: 8px;">
<div style="background: #F8F8F8; line-height: 0; margin-top: 40px; padding: 50.0% 0; text-align: center; width: 100%;">
<div style="background: url(data:image/png; display: block; height: 44px; margin: 0 auto -44px; position: relative; top: -22px; width: 44px;">
</div>
</div>
<div style="margin: 8px 0 0 0; padding: 0 4px;">
<a href="https://www.instagram.com/p/BMNRD1Jh-cw/" style="color: black; font-family: "arial" , sans-serif; font-size: 14px; font-style: normal; font-weight: normal; line-height: 17px; text-decoration: none; word-wrap: break-word;" target="_blank">Testing @taulabs LQG controller on three different frames. This is a more modern approach to control than traditional PID. There is a more complete write-up available here http://buildandcrash.blogspot.com/2016/10/linear-gaussian-quadratic-control-system.html. I'd love to find some good pilots who really want to show what this can do. #lqgcontroller #taulabs #sparky2 #freedom</a></div>
<div style="color: #c9c8cd; font-family: Arial,sans-serif; font-size: 14px; line-height: 17px; margin-bottom: 0; margin-top: 8px; overflow: hidden; padding: 8px 0 7px; text-align: center; text-overflow: ellipsis; white-space: nowrap;">
A video posted by peabody124 (@peabody124) on <time datetime="2016-10-31T00:32:10+00:00" style="font-family: Arial,sans-serif; font-size: 14px; line-height: 17px;">Oct 30, 2016 at 5:32pm PDT</time></div>
</div>
</blockquote>
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script></div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com39tag:blogger.com,1999:blog-1759046512792102553.post-59089840751489684942015-05-12T01:49:00.000-07:002015-05-20T17:30:35.619-07:00TauOSD + VTX<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<b>Sparky2 is available here <a href="http://www.hobbiesfly.com/taulabs-sparky2-0.html">http://www.hobbiesfly.com/taulabs-sparky2-0.html</a></b><br />
<br />
In case you want the video first:<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/128424367" webkitallowfullscreen="" width="500"></iframe>
</div>
<br />
After the amount of fun I had putting a VTX on <a href="http://tps63002/">Brushed Sparky</a>, it got me asking what else would benefit from integration? In the background, I've also been plodding away at a few various revisions of TauOSD. This was inspired by BrainFPV resurrecting and vastly improving the OSD code. The video overlay of that was working fairly nicely, so adding a VTX directly on board seemed like a fun idea.<br />
<br />
<h3>
Features:</h3>
<ul>
<li>Fully graphical OSD with crisp black and white OSD and double buffering</li>
<li>Integrated 32ch 600mW 5.8ghz VTX. Channel selection provided via GCS.</li>
<li>Powered by STM32F4 with enough CPU power to redraw every frame</li>
<li>5V and 12V switching supply that can be used for camera and external VTX. Nice clean power.</li>
<li>Switchable camera input (can be controlled via transmitter)</li>
<li>Runs up to 4S batteries.</li>
<li>Gets data from flight controller via CAN</li>
<li>Serial port available for mavlink telemetry (not implemented yet)</li>
<li>standard 36x36mm footprint</li>
</ul>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiv9y9BBP0f9Y7m1rVLpmOn2jgjRQEN2KUvemTEZKmE-bY5MG4HT101xSLEhZWv9UbD3wa4bXX8b4a7n2o9kTCcpTDBKNWNwuDxC-mYLAx5zcslpDKCT0fbq6wa-DymAAifazzVW9aur1w/s1600/IMG_20150502_130705.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="227" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiv9y9BBP0f9Y7m1rVLpmOn2jgjRQEN2KUvemTEZKmE-bY5MG4HT101xSLEhZWv9UbD3wa4bXX8b4a7n2o9kTCcpTDBKNWNwuDxC-mYLAx5zcslpDKCT0fbq6wa-DymAAifazzVW9aur1w/s400/IMG_20150502_130705.jpg" width="400" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">TauOSD+VTX</td></tr>
</tbody></table>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjNet_3webfFe4Bp4dTC-uvcCSjuD8d9GQd-0gIkNDxeeLFnSsWqG7JF7uj7wN0pCF0n_DFkMgJ6Ty9ep1BeLvSqk3H7k2hCKVZtKuiH1LA6Pss2-C-JmGThRjEzexEzs-C7DBw6Zi5d9s/s1600/tauosd_back.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjNet_3webfFe4Bp4dTC-uvcCSjuD8d9GQd-0gIkNDxeeLFnSsWqG7JF7uj7wN0pCF0n_DFkMgJ6Ty9ep1BeLvSqk3H7k2hCKVZtKuiH1LA6Pss2-C-JmGThRjEzexEzs-C7DBw6Zi5d9s/s320/tauosd_back.jpg" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Back with 32ch module</td></tr>
</tbody></table>
<br />
This creates a really compact setup as you can stack a Sparky2 on top of this and have everything you need for flight, telemetry, OSD, and VTX in a 36x36 footprint (although I'd recommend a heatsink on the OSD). I still don't find an OSD incredibly useful, but the minimal set of things like altitude, battery, current and flight time really are quite useful.<br />
<br />
<table cellpadding="0" cellspacing="0" class="tr-caption-container" style="float: left; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjmI8zk92qcTtP7Pl5S6Rk1-hdj8NGlS8RdAXYPUT8aw7bLdKQlKUbuELlR_QtelS7xWcrToJn7IRMbXkb98U3erdY2Vc6c_MrPAAAFsnaBmrXkER_1CrolvlEjbpTIx-h37wCbIgvcJ-g/s1600/IMG_20150419_183204.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" height="302" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjmI8zk92qcTtP7Pl5S6Rk1-hdj8NGlS8RdAXYPUT8aw7bLdKQlKUbuELlR_QtelS7xWcrToJn7IRMbXkb98U3erdY2Vc6c_MrPAAAFsnaBmrXkER_1CrolvlEjbpTIx-h37wCbIgvcJ-g/s320/IMG_20150419_183204.jpg" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Minimal hardware required for an OSD and FPV system. Sparky2 is powered from the TauOSD+VTX and sends all the information for the overlay.</td></tr>
</tbody></table>
<br />
<br />
<br />
<h3 style="text-align: left;">
Testing:</h3>
I installed both Sparky2 and TauOSD+VTX in my havoc for testing. This is using the 12V supply to a PZ0420 board camera mounted on the front.<br />
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgiRPiu0C_ePR7eqhp0CaDvZY9c3r9YyEyIMtG4XcXVIu6ubmhhx8ZzK3y5MDCv4XrR-hSKlXJuzLXYLkIfCuksu5HAPQknZJ4yJB8jfma8nv1_QeULbQX9n_OQBK9Nbb24uEP_EZt6N2Y/s1600/IMG_20150427_195332.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em; text-align: center;"><img border="0" height="262" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgiRPiu0C_ePR7eqhp0CaDvZY9c3r9YyEyIMtG4XcXVIu6ubmhhx8ZzK3y5MDCv4XrR-hSKlXJuzLXYLkIfCuksu5HAPQknZJ4yJB8jfma8nv1_QeULbQX9n_OQBK9Nbb24uEP_EZt6N2Y/s320/IMG_20150427_195332.jpg" width="320" /></a></div>
<br />
Here it is flying. This is running on a 4S battery directly into the OSD, which is then also powering Sparky2.<br />
<br /></div>
<div style="margin: 8px 0 0 0; padding: 0 4px;">
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/128424367" webkitallowfullscreen="" width="500"></iframe> </div>
<br /></div>
</div>
<br />
So far I'm quite happy with the video, which looks really crisp and clean. The OSD is stable and easy to read (thanks BrainFPV)!<br />
<br />
The previous VTX used a TX5813 module followed by an HMC406MS8G. It was a learning experience to get all the video traces routed carefully at 50 ohm (working out for OSHpark specs), with components placed at various phases along the transmission line. I was happy to see it seems to work well, although I really could do with a VTX power monitor to see if it really hit the spec'd power.<br />
<br />
The latest version uses a really nice 600mW 32ch module which is convenient for supporting all googgles.<br />
<h3 style="text-align: left;">
Future plans</h3>
<ul style="text-align: left;">
<li>Sync the settings back and forth between Sparky2 and TauOSD to allow the awesome settings configuration menu that BrainFPV developed to be used.</li>
<li>Do more flight tests showing off features like video input switching.</li>
<li>Embed telemetry information in the audio stream</li>
</ul>
<br />
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com27tag:blogger.com,1999:blog-1759046512792102553.post-59924299434614887202015-05-07T09:45:00.004-07:002015-05-13T15:13:28.771-07:00Tau Labs and CyPhy "Level Up"<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
It was exciting to see another player adopting Tau Labs at their core with the announcement of the CyPhy LVL 1 <a href="https://www.kickstarter.com/projects/1719668770/cyphy-lvl-1-drone-reinvented-for-performance-and-c?ref=popular">kickstarter</a>. This is a really neat drone project that removes the need for a gimbal while flying by being able to navigate around and remain level. This is a neat idea but traditionally multirotors fly by tilting to generate lateral acceleration. While they are using Tau Labs, they haven't yet released any code, so we can't look there. So how do they do it?<br />
<br />
<b>Note: I am affiliated with Tau Labs not CyPhy or LVL1 so this is all inferred from their press information</b>.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhkAHk5RIMOb5YSDqsTU9tKkFIZBu_eNgHWalsAM_ifuX3gKV861BMFt4yQR8aSgq7k05ouNkOkyeyAvCeyhsj6mXkxiqzmWd-GkpxUFnpm0rGqVCslrru_n4UHkaKH4wgt3H9hm20MFQ4/s1600/IMG_20150507_002503.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto; text-align: center;"><img border="0" height="261" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhkAHk5RIMOb5YSDqsTU9tKkFIZBu_eNgHWalsAM_ifuX3gKV861BMFt4yQR8aSgq7k05ouNkOkyeyAvCeyhsj6mXkxiqzmWd-GkpxUFnpm0rGqVCslrru_n4UHkaKH4wgt3H9hm20MFQ4/s320/IMG_20150507_002503.jpg" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">My vectored thrust hexcopter</td></tr>
</tbody></table>
<div style="text-align: left;">
</div>
<div style="text-align: left;">
Figuring this out seemed like a fun evening challenge, and also highlights that Tau Labs is flexible enough to really make things like this easy. The best way to understand something is to replicate it, so let's dive in.<br />
<br /></div>
<h3 style="text-align: left;">
Traditional system</h3>
So a traditional quadcopter has four motors. The speeds of these four motors are computed based on four inputs: roll torque, pitch torque, yaw torque, and finally total thrust. This is a fully constrained system and has no possible other inputs. There are some ways to permanently alter it. For example many people are experimenting with tilted motors to generate horizontal force while staying closer to level. This allows faster FPV flights while keeping the camera more level (e.g. <a href="http://team-blacksheep.com/products/prod:gemini">TBS Gemini</a>, which also uses Tau Labs).<br />
<br />
You can also make this more flexible but tilting the motors dyamically using a tilt mechanism. For example I put this on <a href="http://buildandcrash.blogspot.com/2013/04/triblivion-and-sparky.html">TriBlivion</a>, which allows you to fly forward controllably while staying level.<br />
<br />
Once you go to a hexcopter, you have an overactuated system: where you have more control outputs than you have desired inputs. For a traditional arrangement of motors (all horizontal, such as Y6 or flat 6) there is no way to use a different mixer and generate more forces. This can be written more formally: there is a matrix that translates from motor RPMs to torques (3 rotation directions) and thrusts (in 3 directions, forward, leftward, and upward) and they cannot be dissociated.<br />
<br />
<h3 style="text-align: left;">
</h3>
<h3 style="text-align: left;">
A more controllable hex</h3>
<div>
This does not have to be the case. If we do not have all the motors parallel, then is it possible to separately control thrust forward (like with tilted motor racing quads) separately from the thrust upward. I saw this <a href="http://www.clubic.com/mag/transports/actualite-765710-cyphy.html">image online</a>:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="http://img.clubic.com/08027256-photo-cyphy-lvl-1.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="http://img.clubic.com/08027256-photo-cyphy-lvl-1.jpg" height="85" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Which shows the side profile in a more informative manner. You can see the front motor is tilted back and the middle motor is tilted forward. If you were to speed up the middle motor while slowing down the back and front motor, you would create no net rotational force while generating a forward force. If you speed up the front and slow down the back motor while speeding up the front motor, you would create a pitching upward torque. If you speed up all three, you create an upward force. So for these three motors you can separate forward force, vertical force, and pitching torque.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<i>TL;DR: 6 motors means 6 controls!</i></div>
<div class="separator" style="clear: both; text-align: left;">
<i><br /></i></div>
<div class="separator" style="clear: both; text-align: left;">
As an aside, basically anyone that has been flying a V-tail has been doing this type of vectored thrust for years. With a V-tail you have two motors at the back that are angled and fighting each other. Combined they create a pitch force. Their difference creates a yaw force. However this is not an over-actuated system -- it has four motors and four controls.</div>
<div class="separator" style="clear: both; text-align: left;">
<i><br /></i></div>
<h3 style="clear: both; text-align: left;">
</h3>
<h3 style="clear: both; text-align: left;">
Let's math it</h3>
<div class="separator" style="clear: both; text-align: left;">
Now let's try and extend this to a general solution with 6 motors and also while at it solve for the mixer that would allow us to control things.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Each motor will have a position -- in this case spaces at 60 degrees along a unit circle (although since this is a general solution we can change this later and re-derive it). The front two motors will be tilted backward and slightly outward (adding some yaw and lateral maneuvering). The middle is tilted inward and force, and the back are only tilted inward.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Put these into quaternion notation, we can then do a little bit of math to convert their thrust into the frame reference plane:</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<pre class="brush:matlabkey">
for i = 1:N
q(i,:) = RPY2Quaternion([mot_r(i), mot_p(i), 0]);
% the last column of the matrix that rotates from the body (motor)
% to the earth (hexcopter) reference frame gives the force it generates
% in each axis
Rbe = Q2Rbe(q(i,:));
force(i,:) = Rbe(:,3)';
end
</pre>
</div>
<br />
Now those thrusts can be used to compute the lateral forces. However, they also create torques on the frame which we want to solve for. The yaw force from each motor is a mixture of two components. the first is from the drag of the blade on the air creating a rotation force on the frame that will be proportional to the Z force. the second and larger will be the cross product of the position of that motor relative to the center of mass. Since I plan to use this with tiny props, the thrust component of the yaw will be dominant and I will ignore the drag.
<br />
<br />
<pre class="brush:matlabkey">
k1 = 0.0; % the drag component
k2 = 1;
for i = 1:N
torques(i,:) = cross(force(i,1:3)', pos(i,:)');
torques(i,3) = k2 * torques(i,3) + k1 * CW(i) * force(i,3);
end
</pre>
</div>
<br />
We can visualize these forces and torques in 3D:<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5yN2VQOEoVR-qPXtFdtvlDiETit4etsfyHJRinaCOuyTqpkk0qRrB_2llqB3lmHucUf9HxYvNze4s2i53e9FSgrk4qPMfA_72kQ6ubcEIssVsSH8DUi9WYEsDwr21AxHlw_kFMl-H_Yw/s1600/forces_and_torques.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="300" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5yN2VQOEoVR-qPXtFdtvlDiETit4etsfyHJRinaCOuyTqpkk0qRrB_2llqB3lmHucUf9HxYvNze4s2i53e9FSgrk4qPMfA_72kQ6ubcEIssVsSH8DUi9WYEsDwr21AxHlw_kFMl-H_Yw/s400/forces_and_torques.png" width="400" /></a></div>
<br />
From this, we can generate a matrix that takes the set of motor RPMs and computes the torques and accelerations:
<br />
<br />
<pre class="brush:matlabkey">
k1 = 0.0; % the drag component
% W maps from 6 motors to six control outputs
% roll, pitch, yaw, forward, sideways, up
W = [torques'; ...
force'];
</pre>
<br />
Then finally using the pseudo-inverse (or since this is 6x6 we can use true inverse) we can calculate mixer matrix that will let us take the desired roll, pitch, yaw rates, and forward, sideways acceleration and solve for the motor settings.
<br />
<br />
<pre class="brush:matlabkey">
k1 = 0.0; % the drag component
M = W'*(W*W')^-1;
</pre>
<br /></div>
The result gives us a nice sensible mixer matrix
<br />
<pre class="brush:matlabkey">
k1 = 0.0; % the drag component
M =
0.0068 0.0034 0.0084 -0.6356 -0.9976 0.1764
-0.0068 0.0034 -0.0084 -0.6356 0.9976 0.1764
-0.0060 0.0034 0.0101 1.2963 -0.0296 0.1764
0.0011 -0.0068 -0.0115 -0.6433 -0.9510 0.1785
-0.0011 -0.0068 0.0115 -0.6433 0.9510 0.1785
0.0060 0.0034 -0.0101 1.2963 0.0296 0.1764
</pre>
<br />
So basically we multiply this matrix by the desired behavior (roll, accel, etc) and get the motor speeds. BTW as a sanity check, if we remove the tilts the result says singular matrix and makes no sense. That's because a traditional (non-tilted hex) cannot do this.<br />
<br />
<h3 style="text-align: left;">
Let's build it!</h3>
<div>
Ok, so now we know these motor positions create a controllable system, let's build it! I went ahead and whipped this up in no time in OpenSCAD. You can download your own (or change the motor parameters) <a href="http://www.thingiverse.com/thing:814357">on Thingiverse</a>.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjocu4a4JJf9W1XrGsFqSxpsqHMuQz4mxfetNCPpTItpILGh3OiwHheAOYtbfA0ZcoWGCxfW39_7y4S3AjmeRLH-J7hY1faeSR-oQPCEJFl4zVs0tPGNk_K2rn_UqudpJw1uJD16Rd_H6Y/s1600/Screen+Shot+2015-05-06+at+4.18.51+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="207" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjocu4a4JJf9W1XrGsFqSxpsqHMuQz4mxfetNCPpTItpILGh3OiwHheAOYtbfA0ZcoWGCxfW39_7y4S3AjmeRLH-J7hY1faeSR-oQPCEJFl4zVs0tPGNk_K2rn_UqudpJw1uJD16Rd_H6Y/s1600/Screen+Shot+2015-05-06+at+4.18.51+PM.png" width="320" /></a></div>
<div>
<br /></div>
<div>
Ninety minutes of printing later, I had my motors in position. Luckily I'd be planning on making a hex version of <a href="http://buildandcrash.blogspot.com/2015/03/brushedsparky-v02.html">BrushedSparky</a> using a 3d printed attachment and already have the 6 necessary brushed outputs. So let's go ahead and mount this.</div>
<div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhkAHk5RIMOb5YSDqsTU9tKkFIZBu_eNgHWalsAM_ifuX3gKV861BMFt4yQR8aSgq7k05ouNkOkyeyAvCeyhsj6mXkxiqzmWd-GkpxUFnpm0rGqVCslrru_n4UHkaKH4wgt3H9hm20MFQ4/s1600/IMG_20150507_002503.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="261" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhkAHk5RIMOb5YSDqsTU9tKkFIZBu_eNgHWalsAM_ifuX3gKV861BMFt4yQR8aSgq7k05ouNkOkyeyAvCeyhsj6mXkxiqzmWd-GkpxUFnpm0rGqVCslrru_n4UHkaKH4wgt3H9hm20MFQ4/s320/IMG_20150507_002503.jpg" width="320" /></a></div>
<br /></div>
<div>
<br /></div>
<h3 style="text-align: left;">
Flight!</h3>
<div>
Next we use the custom mixer calculated in matlab with arbitrary scales applied to get normal ranges. This scaling is equivalent to changing the PIDs and we will autotune this at the end to get it better. At this point, it should not have as much unrequested forward and sidways motion. However, this isn't fun yet! We are still flying like a traditional system.<br />
<br />
I then set up the slider on my transmitter to map to Accessory0 and added the entries into the mixer so that controlled forward thrust. Later if this starts flying really well I can actually make the slider provide roll and pitch and use the roll and pitch sticks on Accessory0,1 to fly around purely level.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiU1V_rF45qZ4VkgjtjiA9nDwDFo8Mc9FygARwc1kYjyYyd5uR3whNLJlFuOfG_SKILvZiBeiVr55Dej7j3PVMTomAFn87dJWNB05hTN4X-Eikmn0-rubrlRVSstevviCBdfoAEXPtO_c0/s1600/Screen+Shot+2015-05-07+at+9.22.36+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="320" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiU1V_rF45qZ4VkgjtjiA9nDwDFo8Mc9FygARwc1kYjyYyd5uR3whNLJlFuOfG_SKILvZiBeiVr55Dej7j3PVMTomAFn87dJWNB05hTN4X-Eikmn0-rubrlRVSstevviCBdfoAEXPtO_c0/s320/Screen+Shot+2015-05-07+at+9.22.36+AM.png" width="283" /></a></div>
<br />
At this point there was no more excuse to not fly :). It still can do with some tuning, but here are the initial flights. Here I'm using <a href="http://buildandcrash.blogspot.com/2015/03/brushedsparky-v02.html">Brushed Sparky's</a> native <a href="https://vimeo.com/124850842">OpenLRS support</a>. It has a tiny chip antenna mounted which is convenient for keeping it low profile.<br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/127173233" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
You can see when I enable forward mode, there is a tendency to climb. At this point I think I'm hitting issues because of the linearization of the mixer. For small changes where the motors are nearly running at the same speed this is appropriate. However, for large forward inputs that makes the middle motor run quite high (which creates excessive thrust because that is super-linear with input) and the decrease in the front and back motors is not sufficient. This might be fixable with some static non-linearities in the mixer (e.g. sqrt) or could require a more sophisticated controller.<br />
<br />
A second issue that is related but probably more about weight-to-thrust is that as when I generate enough forward thrust to be entertaining, it starts rocking in pitch a bit. I need to get some logs to confirm this, but I'm pretty sure the middle motor is running and practically shutting off the front and back motors.<br />
<br />
Anyway, it doesn't fly wonderfully yet - but this is 12 hours after I got the idea ;-). I think it is a pretty solid demonstration of how you can take funny motor positions and generate a mixer to get new control dimensions, and a pretty nice proof of principle.<br />
<br />
<h3 style="text-align: left;">
Conclusion</h3>
<div>
CyPhy have a really cool frame design, and it really shows off the versatility of Tau Labs that we can control airframes like this that weren't conceived of when we wrote the code. I definitely need to play with mine more to get it better tuned in and explore doing some level FPV flying. It might be that something a bit more substantive with brushless motors might be required to have sufficient thrust. I'll also be interested to see about flight times and efficiency. Having the motors fight each other (some pushing forward and some backward) is definitely burning batteries.<br />
<div>
</div>
<br />
Speaking of thrust, I will be really really curious to see more videos of their frame flying in windy conditions. By using thrust vectoring like this to maneuver, the maximal amount of forward thrust is much less than traditional hexcopter navigation. For example, with a whole hex tilted at 30 degrees you get essentially 0.5 * gravity acceleration forward. On a vectored design like this for max forward thrust (while keeping the thing level) is substantially less than that.<br />
<br />
Also behavior in wind will be interesting. An advantage of a gimbal is you have a relatively small mass that simply has to not rotate (it's natural state). For example I took this video at the beach in extremely stable conditions with Sparky Brushless Gimbal Controller:<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/66987484" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Even though it is getting hammered by wind, the video is rock solid. I'm not sure you can ever get a stabilization controller so tight that you won't have wind moving it, so lacking that gimbal to isolate the motion might be tough.<br />
<br />
I'm sure there are some clever tricks that CyPhy developed to get really nice performance. The clips in their demo reel look really nice. Tau Labs is GPL, so hopefully they will release their code changes at some point so we can see what they were!<br />
<br />
<h3 style="text-align: left;">
Future!</h3>
</div>
<div>
So as much as vectored thrust is fun, I really like traditional flying. The control authority of pointing the motors in the direction you want to haul ass is huge. However, this motivated me to work out something I've wanted forever: <i>how to take an arbitrary set of motor positions and angles and calculate the mixer</i>. </div>
<div>
<br /></div>
<div>
This is useful for some simple reasons: got your custom shaped frame, weird H, V tail, etc? Now we can solve for the mixer. Even more excitingly, this is exactly what is required to recompute the mixer on the fly for something like a tilt rotor airframe :). <a href="http://buildandcrash.blogspot.com/2013/04/triblivion-and-sparky.html">TriBlivion</a> might be getting pulled back out of storage.</div>
</div>Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com219tag:blogger.com,1999:blog-1759046512792102553.post-66051449519290195262015-03-27T08:10:00.000-07:002015-03-27T08:26:35.536-07:00BLHeli OneShot Quantitative testing<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
I <a href="http://buildandcrash.blogspot.com/2015/01/oneshot125-quantitative-testing.html">previously did some tests</a> with KISS ESCs comparing the performance with OneShot to normal PWM modes showing Tau Labs implementation has a nice low latency from sensor update to output pulse, as well as the fact that OneShot results in better system performance.<br />
<br />
Since then, I've wanted to replicate it with BLHeli's OneShot mode and see if it is has similar benefits. I got some BearHug ESCs, which <b>unfortunately are quite unreliable</b> and needed a few to be replaced which slowed things down. (In retrospect I wish I'd used <a href="http://www.banggood.com/BLHeli-12A-4-In-1-Brushless-ESC-Speed-Controller-p-949609.html">these four in one ESCs</a>). Anyway, I eventually got a working set of four and soldered the programming cable to them. I used my <a href="https://oshpark.com/shared_projects/5MMpnB1l">KISS PDB board</a> again which provides a 5V BEC as well as current/voltage monitoring.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4edV-nlE-4OetWCOSmTTlng4LEQdFs4W8PIuAIN_VLTz2stQYIoWQ7bDTCIBPTyNvmOPQqZk2Qg2EOu9yf9Y12UT4aQBf9fVN0RGQlzPs8SHxZinlAIGATqc0re0ziNvytBHW07neJOk/s1600/IMG_20150326_201448.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4edV-nlE-4OetWCOSmTTlng4LEQdFs4W8PIuAIN_VLTz2stQYIoWQ7bDTCIBPTyNvmOPQqZk2Qg2EOu9yf9Y12UT4aQBf9fVN0RGQlzPs8SHxZinlAIGATqc0re0ziNvytBHW07neJOk/s1600/IMG_20150326_201448.jpg" height="189" width="320" /></a></div>
<br />
I put them on a <a href="http://us.banggood.com/Wholesale-Warehouse-H250-ZMR250-250mm-Carbon-Fiber-Mini-Quadcopter-Multicopter-Frame-Kit-wp-Usa-933185.html">ZMR250</a> frame using and this pretty <a href="http://www.banggood.com/Eachine-700TVL-13-Cmos-FPV-110-Degree-Camera-w32CH-Transmission-p-965760.html">nice cheap FPV</a> system that seems to work fairly well. I'm also using these <a href="http://hobbyking.com/hobbyking/store/__69296__Emax_PM1806_2300Kv_Brushless_Multi_Rotor_Motor_Set_1xCW_1xCCW_.html">new plastic motors</a> that are dirty cheap (30$ for four). They are spinning 5 inch props.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiK7UvR2WWqLNwUeKMUirxsKxfL9jc1N9MB4LuSDB-JFmSEXHd9rVskFFSUGSM1O42Ahi_sdwTy6nfxnjpmryyovTshiDY1L81UMzbOIzQZmFVMhwL0zdF9yINdKLiHgGbUrFDiM8nI6co/s1600/IMG_20150326_201609.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiK7UvR2WWqLNwUeKMUirxsKxfL9jc1N9MB4LuSDB-JFmSEXHd9rVskFFSUGSM1O42Ahi_sdwTy6nfxnjpmryyovTshiDY1L81UMzbOIzQZmFVMhwL0zdF9yINdKLiHgGbUrFDiM8nI6co/s1600/IMG_20150326_201609.jpg" height="219" width="320" /></a></div>
<br />
Of course, it's running a <a href="http://taulabs.org/">Tau Labs</a> <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky2</a> for the flight controller and <a href="http://buildandcrash.blogspot.com/2015/02/brushedsparky-sparky2-microquads.html">TauLinkModule</a> for control.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgtag2tjplUwjCBOHO0SqhagMTWXSyjfWeaD3Syh694ft84RA4dKmb5DgBCRyF78Cnc9rTPo-Shwy_UHHnEyGgRvGVDsX49B481SemtmveemgGRNpDm0LSRsDnUuwEP49pDMGGc_sJLXGk/s1600/IMG_20150326_214157.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgtag2tjplUwjCBOHO0SqhagMTWXSyjfWeaD3Syh694ft84RA4dKmb5DgBCRyF78Cnc9rTPo-Shwy_UHHnEyGgRvGVDsX49B481SemtmveemgGRNpDm0LSRsDnUuwEP49pDMGGc_sJLXGk/s1600/IMG_20150326_214157.jpg" height="240" width="320" /></a></div>
<br />
The PDB and ESCs fit quite nicely under the flight controller and leave room for the programming cables. And here it is all put together with the FPV system.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjNzJ77uPRpQ7gGzPHh3DG_2QltTBbtv69MGqAZJpvXjhssUhdPTNeYehuaDDR1p8SQpSeL5bcnz36b5sf2wzUxs3HsJa56GXctIE_1qhFv4_fn_FPnJnfNG7p9yhV7nFsrfXTHARLQ9tM/s1600/IMG_20150326_234431.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjNzJ77uPRpQ7gGzPHh3DG_2QltTBbtv69MGqAZJpvXjhssUhdPTNeYehuaDDR1p8SQpSeL5bcnz36b5sf2wzUxs3HsJa56GXctIE_1qhFv4_fn_FPnJnfNG7p9yhV7nFsrfXTHARLQ9tM/s1600/IMG_20150326_234431.jpg" height="240" width="320" /></a></div>
<br />
The antenna placement is probably a terrible idea ... the VTX is connected with velcro so can pop off in a crash. I'll redo this once some cloverleaf antennas arrive.<br />
<h4 style="text-align: left;">
Flashing and Configuring</h4>
<div>
Once it was all put together, I followed this nice video by AKFreak on how to flash the ESCs (using a VM). This was actually the first time I'd played with an Arduino other than the one in my Shapeoko.</div>
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="315" src="https://www.youtube.com/embed/0ioKhY77bMo" width="560"></iframe></div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: left;">
I programmed all of them with BLHeli 13.1</div>
<div style="text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjB0sM4zYO2dcdLm5H_9w3q447UUQjvxVSARE0dnnXAwotrLchRbe-kyode_42otedO9ia3933iomNMVrz0T77VuQ_o2dMNech62tjkLlegzC4gQuhSWKvZ1f3dwpyzyFciLYQSj-AExz0/s1600/IMG_20150327_001949.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjB0sM4zYO2dcdLm5H_9w3q447UUQjvxVSARE0dnnXAwotrLchRbe-kyode_42otedO9ia3933iomNMVrz0T77VuQ_o2dMNech62tjkLlegzC4gQuhSWKvZ1f3dwpyzyFciLYQSj-AExz0/s1600/IMG_20150327_001949.jpg" height="240" width="320" /></a></div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: left;">
I went ahead and enabled Damped Light mode:</div>
<div style="text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjnqsfF4Yj1ZKSUf9gVV_YspbFZYZPOyOdFPNY0hvQfdTr2IyAJJix3ATkaM3enaQiS8ECbTnmrY-55oGrwrvMk2WT_DM1L8yR9uVyFcZzHOoPfmzGz5j3ArxMdrBFyJoM5djcs3RqXlPM/s1600/blheli+settings.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjnqsfF4Yj1ZKSUf9gVV_YspbFZYZPOyOdFPNY0hvQfdTr2IyAJJix3ATkaM3enaQiS8ECbTnmrY-55oGrwrvMk2WT_DM1L8yR9uVyFcZzHOoPfmzGz5j3ArxMdrBFyJoM5djcs3RqXlPM/s1600/blheli+settings.png" height="221" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h4 style="clear: both; text-align: left;">
Results:</h4>
<div class="separator" style="clear: both; text-align: left;">
I used the <a href="https://vimeo.com/104806460">Tau Labs system identification</a> performance to measure the latency of the ESC responses with regular PWM and OneShot125 mode.</div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: left;">
<b>Regular (PWM High)</b></div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjvHjsheUufs6ws5lpxL6S1yqgcFRoo59f7qsRAtVSfb3rY1bqMhL-8peqbNQWywrgPb5l9h-PX_5ubhGuU7piQpl_vsmXCuDWIOszQ6TBeB99f3n29fPXynfEi_mQ5Yl19aeIN4zCxyGY/s1600/regular1.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjvHjsheUufs6ws5lpxL6S1yqgcFRoo59f7qsRAtVSfb3rY1bqMhL-8peqbNQWywrgPb5l9h-PX_5ubhGuU7piQpl_vsmXCuDWIOszQ6TBeB99f3n29fPXynfEi_mQ5Yl19aeIN4zCxyGY/s1600/regular1.png" height="84" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiIs_TycnwnanrKoZlN2NIvdC-i-JyJgNsGtXeaeoVBhHbP1vqu13Ex0EFTsIkdw8uZf2N-F8fjA1fPpQPnufxuV4O1UNSI4zsvU2oXCVihaMhvkjMaITufiGhRW2r4YaXxEkQD5Mzsq_4/s1600/regular2.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiIs_TycnwnanrKoZlN2NIvdC-i-JyJgNsGtXeaeoVBhHbP1vqu13Ex0EFTsIkdw8uZf2N-F8fjA1fPpQPnufxuV4O1UNSI4zsvU2oXCVihaMhvkjMaITufiGhRW2r4YaXxEkQD5Mzsq_4/s1600/regular2.png" height="74" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhNbz2IdLxH3T5EolHjFLH8-tTN9YThA5K_m4LBC_oIUzHIJuFI_wCK0W6eCmleb25j1JyfVWyTuoimaFLOAD8I624G3ryQGb1f_AwB_pWs5WpmgkKauy9KC45stP7T2IHGGO88Zh9Q7l0/s1600/regular3+-+fresh+battery.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhNbz2IdLxH3T5EolHjFLH8-tTN9YThA5K_m4LBC_oIUzHIJuFI_wCK0W6eCmleb25j1JyfVWyTuoimaFLOAD8I624G3ryQGb1f_AwB_pWs5WpmgkKauy9KC45stP7T2IHGGO88Zh9Q7l0/s1600/regular3+-+fresh+battery.png" height="75" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: left;">
<b>One Shot (PWM High)</b></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhpTIL0TMpd4GGuwqIHY9AdVGM3dCQlvNGywp2am95jCOrezdff87MMX2S8Vl5lkZPCeg0vuY6JmAX5csOC0Nsx6PKwm4R4rcvlv04RZ3t4N3YTx10g4WXchmpQ-BLBhm2DiwAvU-QUDwI/s1600/oneshot1.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhpTIL0TMpd4GGuwqIHY9AdVGM3dCQlvNGywp2am95jCOrezdff87MMX2S8Vl5lkZPCeg0vuY6JmAX5csOC0Nsx6PKwm4R4rcvlv04RZ3t4N3YTx10g4WXchmpQ-BLBhm2DiwAvU-QUDwI/s1600/oneshot1.png" height="95" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhu-iVBP8urUyAkltaYvAI_pm7umay5JIFoe_nRuJujBS0wbRIhdHKLEmlSx7viWg8p_Lj7gKU01d9J11FPjEMa1o4tTF7nJ6FFWvEpWDFLTJmRPo4X3ThGyrYMKauQenGZP_UqkFEK2RM/s1600/oneshot2+-+11.5V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhu-iVBP8urUyAkltaYvAI_pm7umay5JIFoe_nRuJujBS0wbRIhdHKLEmlSx7viWg8p_Lj7gKU01d9J11FPjEMa1o4tTF7nJ6FFWvEpWDFLTJmRPo4X3ThGyrYMKauQenGZP_UqkFEK2RM/s1600/oneshot2+-+11.5V.png" height="95" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjtYcTJEID6FCXfodVDF2r6av32M8zh6NNAfk3tgYCFp2qoZp-y0PMDx5kQdVBtBk-ECAFdVBABiaVl98aqSwDhZiKttnc1iu10sBIFNpMF4PfhLUFoY37QkW6cDrK0ACMTKjKcomisxPg/s1600/oneshot3+-+11.3V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjtYcTJEID6FCXfodVDF2r6av32M8zh6NNAfk3tgYCFp2qoZp-y0PMDx5kQdVBtBk-ECAFdVBABiaVl98aqSwDhZiKttnc1iu10sBIFNpMF4PfhLUFoY37QkW6cDrK0ACMTKjKcomisxPg/s1600/oneshot3+-+11.3V.png" height="95" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: left;">
<b>One Shot (Damped Light)</b></div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: left;">
This was done over two batteries so a range of voltages, although one of the slower outliers was actually with a fairly charged battery.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh2IuyJyeL_zyXiDtkDVP-Mb6AiBRjfo8-SD_KnLbjjckbLJh7EyQD5qXj-CpOhmRV9T-RjPs6NrT6Y5HeKVd5EwgUZFyX0P7ZSUbfNrR2-qvVqUjNcWoBW0ah-OxzEcXD9IDDsbLI0wgw/s1600/oneshot2+-+damped+-+11.9V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh2IuyJyeL_zyXiDtkDVP-Mb6AiBRjfo8-SD_KnLbjjckbLJh7EyQD5qXj-CpOhmRV9T-RjPs6NrT6Y5HeKVd5EwgUZFyX0P7ZSUbfNrR2-qvVqUjNcWoBW0ah-OxzEcXD9IDDsbLI0wgw/s1600/oneshot2+-+damped+-+11.9V.png" height="95" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjW4VBPwxyLn3jGkYOA-2IaLIHb2gCiQFKz2kKwt4Yx723FfQCPnutPV9hbSwjYSgIQPi94VfXIqwp5zDSva0RMTa1qPfX_2issMbqOSk5Eh1mB_pAt90fVBIem4j9dZvFiwMOC13p9rfI/s1600/oneshot3+-+damped+-+11.61.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjW4VBPwxyLn3jGkYOA-2IaLIHb2gCiQFKz2kKwt4Yx723FfQCPnutPV9hbSwjYSgIQPi94VfXIqwp5zDSva0RMTa1qPfX_2issMbqOSk5Eh1mB_pAt90fVBIem4j9dZvFiwMOC13p9rfI/s1600/oneshot3+-+damped+-+11.61.png" height="95" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjNANn3kbyQuBk1c0NWJwv7wjVVykC2BQQjgv0PRchBjMHRPIZCnb9nOLPQ_-3NwI_PPz3aKlJq7DtmaytldfTgNRZ98JyeUK1FBLiMPcNj99g98hnPucukHrKZFhxV6dS6OFUd5BK6xJQ/s1600/oneshot4+-+damped+-+11.40V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjNANn3kbyQuBk1c0NWJwv7wjVVykC2BQQjgv0PRchBjMHRPIZCnb9nOLPQ_-3NwI_PPz3aKlJq7DtmaytldfTgNRZ98JyeUK1FBLiMPcNj99g98hnPucukHrKZFhxV6dS6OFUd5BK6xJQ/s1600/oneshot4+-+damped+-+11.40V.png" height="96" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgua0t7JfrINkvZZ2RwS2GvbEGpQH6beSH4SfEcs2xMD_8GiFcNrlLN-A4Zmc_YNUWjzNuUp8POsbkQ32jcerGnGaTa-7G8-2jPeYspu_R3wvj9WWcMmg0KWgzw2epAD3WT3MoRicwMZwM/s1600/oneshot5+-+damped+-+11.22V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgua0t7JfrINkvZZ2RwS2GvbEGpQH6beSH4SfEcs2xMD_8GiFcNrlLN-A4Zmc_YNUWjzNuUp8POsbkQ32jcerGnGaTa-7G8-2jPeYspu_R3wvj9WWcMmg0KWgzw2epAD3WT3MoRicwMZwM/s1600/oneshot5+-+damped+-+11.22V.png" height="96" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgk7G38wLYQ7qOsfNEbqu6SHZ89oS8UhWPn6r7UuiNybstKqlmu6tO5P6T3lL_HgJLXU-VfK3LJkLx2opHNLMj9d2k7NR3gvM-GMLgX1JUtiWcAnMDED8IUOpfwJoy5QK6DYFTSyhNSyTY/s1600/oneshot6+-+damped+-+11.1V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgk7G38wLYQ7qOsfNEbqu6SHZ89oS8UhWPn6r7UuiNybstKqlmu6tO5P6T3lL_HgJLXU-VfK3LJkLx2opHNLMj9d2k7NR3gvM-GMLgX1JUtiWcAnMDED8IUOpfwJoy5QK6DYFTSyhNSyTY/s1600/oneshot6+-+damped+-+11.1V.png" height="94" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiyVFgzI-4N9W1IydzCGoIhjm0ww8k__KrGOKK4dshnmHTV3LtUqBnY4dG7iZYemTsE7qrpbvtsG407kdEYLqeFHLqsfLWag0dWP_XLXJuaDdrGSeE6HsRTVy7xIbRQZemivHL7upnfAQA/s1600/onshot1+-+damped+-+11.15V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiyVFgzI-4N9W1IydzCGoIhjm0ww8k__KrGOKK4dshnmHTV3LtUqBnY4dG7iZYemTsE7qrpbvtsG407kdEYLqeFHLqsfLWag0dWP_XLXJuaDdrGSeE6HsRTVy7xIbRQZemivHL7upnfAQA/s1600/onshot1+-+damped+-+11.15V.png" height="97" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<b>Regular (Damped Light)</b></div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjgWZdUQJLoSotnfjT3pBD1Mc_34QpCgPJ7wToyB1xha-wtBXaebib7X0MoYY2CJE6PKk12zBMmk5VN8I4_P63f5IZKNZEacO8o6TmOUXdHYERYuLgaiiQoe5HrfW45yUnjP7qk2bhoA4s/s1600/regular+-+damped+-+11.9V.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjgWZdUQJLoSotnfjT3pBD1Mc_34QpCgPJ7wToyB1xha-wtBXaebib7X0MoYY2CJE6PKk12zBMmk5VN8I4_P63f5IZKNZEacO8o6TmOUXdHYERYuLgaiiQoe5HrfW45yUnjP7qk2bhoA4s/s1600/regular+-+damped+-+11.9V.png" height="95" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<b><br /></b></div>
<div class="separator" style="clear: both; text-align: left;">
At this point the BearHugs were becoming incredibly unreliable and dropping out of flight during autotune so I couldn't repeat it 3 times. Eventually I smelt the magic smoke and just gave up.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h4 style="clear: both; text-align: left;">
Conclusion:</h4>
<div>
<i>BearHug ESCs are really not reliable :( I've burnt so many hours trying to get flying on these. Can someone recommend alternatives that run BLHeli and are good for fast switching?</i></div>
<div>
<i><br /></i></div>
<div>
<u>Average Tau:</u></div>
<div>
Regular (PWM High): 0.034 (s)</div>
<div>
One Shot (PWM High): 0.028 (s)</div>
<div>
Regular (Damped Light): 0.038 (s) -- note this is only one trial</div>
<div>
One Shot (Damped Light): 0.028</div>
<div>
<br />
I'm not comfortable running statistics on this since the ESCs failed and I didn't get enough trials. There was more spread in the data than I'd have expected that wasn't explained by battery sag. One of the good regular runs was 0.029 and a two of the One Shot (damped) runs were greater than > 0.03. However, on average OneShot definitely seems to be trending in the right direction.<br />
<br /></div>
<div>
That being said, enabling OneShot consistently improves performance with these ESCs. The performance improvement was actually greater than for KISS (17% improvement) although it is hard to say if that is because of greater improvement for OneShot or worse performance for regular. I'd have to compare on the same motors / frame. I'd be curious to see if Damped Light makes more of a difference on larger props.</div>
<div>
<br /></div>
<div>
The autotune settings were really snappy and I just wish I could trust this thing to stay in the air for five minutes (or now to even power up).<br />
<br />
TL;DR: OneShot with BLHeli seems like a worthwhile improvement if you want that last ounce of performance.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<b><br /></b></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com18tag:blogger.com,1999:blog-1759046512792102553.post-21741216372597994362015-03-25T10:59:00.000-07:002015-05-20T12:06:01.421-07:00BrushedSparky v0.2<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div class="separator" style="clear: both; text-align: center;">
<b style="background-color: white; color: #222222; font-family: Arial, Tahoma, Helvetica, FreeSans, sans-serif; font-size: 13.1999998092651px; line-height: 18.4799995422363px; text-align: left;"><a href="http://www.hobbiesfly.com/taulabs-sparky2-0.html" style="color: #888888; text-decoration: none;">you can purchase Sparky2 here</a></b></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjRFzDUVtvy_H2Ukmu8bk02pj7hs3mMkVzCpnODGspjR5VWwlNXQMhMk8O-vVF1VSd_GOI2o2eAB2QhvrHbwjM10lvypgMOnt_MOQ5_TPqeBFqAhAo-yWHoUU_a302gb3dsAQFmkvhdybI/s1600/IMG_20150321_141627.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="224" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjRFzDUVtvy_H2Ukmu8bk02pj7hs3mMkVzCpnODGspjR5VWwlNXQMhMk8O-vVF1VSd_GOI2o2eAB2QhvrHbwjM10lvypgMOnt_MOQ5_TPqeBFqAhAo-yWHoUU_a302gb3dsAQFmkvhdybI/s1600/IMG_20150321_141627.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
BrushedSparky version 0.2 arrived a few days ago. </div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj7SSkI04b1j57rmy__dd_ix4iAM6RPtQlLBNOXkddQFiMdFaz-g6Yz7S9oPuludAQgENl5-jb2KW9uhOd01IUib6AaXhBxAUtl_dpQ2qlCQL88VesvL9q2gAyb4BIPvJby49GMdTFpAvo/s1600/IMG_20150322_163713.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="252" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj7SSkI04b1j57rmy__dd_ix4iAM6RPtQlLBNOXkddQFiMdFaz-g6Yz7S9oPuludAQgENl5-jb2KW9uhOd01IUib6AaXhBxAUtl_dpQ2qlCQL88VesvL9q2gAyb4BIPvJby49GMdTFpAvo/s1600/IMG_20150322_163713.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<h4 style="clear: both; text-align: left;">
Improvements</h4>
<div class="separator" style="clear: both; text-align: left;">
There are a number of improvements over the <a href="http://buildandcrash.blogspot.com/2015/02/brushedsparky-sparky2-microquads.html">previous revision</a>.</div>
<div class="separator" style="clear: both; text-align: left;">
</div>
<ul style="text-align: left;">
<li>A bigger motor mount hole allows for stronger mounts.</li>
<li>Using a 1.2 mm PCB shaves a bit of weight off. </li>
<li>Changed the 5V step up regulator for a new one that is more efficient (and doesn't hum).</li>
<li>Using a more available VTX module so I can build more :)</li>
<li>Shuffled some components around for a slightly slimmed profile (also got a stencil to make it faster to populate).</li>
<li>Current monitoring (enables mAh consumed calculation)</li>
<li>Switch to disable VTX for flying LOS</li>
<li>VTX channel selection via the FC</li>
<li>LEDs on the arms for following via FPV</li>
<li>Two additional PicoBlade connectors for clipping arms to it and making a hex. Also two more buffered outputs on the back such as for LEDs.</li>
</ul>
<br />
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgXAops92FG8zJtbuiQ4N6-8MuzPso6PEcX1s0yd8-us7HwzBNu1CHCIqsNLzUpHLnO0NWJryZtGG0YmBQqHohxxBNOAqTF8aP4cW9mjO5IW1BDqHe6bf1FSfScwVBWcyjqnGhKtonUmdg/s1600/IMG_20150321_123916.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgXAops92FG8zJtbuiQ4N6-8MuzPso6PEcX1s0yd8-us7HwzBNu1CHCIqsNLzUpHLnO0NWJryZtGG0YmBQqHohxxBNOAqTF8aP4cW9mjO5IW1BDqHe6bf1FSfScwVBWcyjqnGhKtonUmdg/s1600/IMG_20150321_123916.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5UJvdytQEf8qzT4lNpogpw9TFnDtjq7u_zDAWE4Y4uzZkA369CxuOVrZRReSLnW9VEJgPKqG2Y4CPRjMvUci0pkglW-8xET1A9PxaNOqtQ_YwTbtspdxqjg5OUQfQgpAYPat4Da6j-PM/s1600/IMG_20150322_162019+(1).jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="145" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5UJvdytQEf8qzT4lNpogpw9TFnDtjq7u_zDAWE4Y4uzZkA369CxuOVrZRReSLnW9VEJgPKqG2Y4CPRjMvUci0pkglW-8xET1A9PxaNOqtQ_YwTbtspdxqjg5OUQfQgpAYPat4Da6j-PM/s1600/IMG_20150322_162019+(1).jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
I'm still controlling it via Tau Link Module, which gives me voltage, current, mAh remaining (as well as logging) on my phone relayed using the module in the transmitter. See the <a href="http://buildandcrash.blogspot.com/2015/02/brushedsparky-sparky2-microquads.html">previous</a> writeup for more information. Quite convenient since it gives me audio alerts. The new revision of Tau Link Module also has SPort support so hopefully I get this information on the Taranis soon.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj34p4Y1eSEVYPXqzLS8lRcCnUhPRSiFr-mVjSznkwCf6Fw7cbfQU0ELARVZf3vJKDLzJKImAY5VxXcQt6XspNjTIvQ5MBGAPuqfI17Ai_B3iDNcqKyeXnmw9AY6LPtlXFxe2uzmmcTAMU/s1600/IMG_20150228_100622.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="313" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj34p4Y1eSEVYPXqzLS8lRcCnUhPRSiFr-mVjSznkwCf6Fw7cbfQU0ELARVZf3vJKDLzJKImAY5VxXcQt6XspNjTIvQ5MBGAPuqfI17Ai_B3iDNcqKyeXnmw9AY6LPtlXFxe2uzmmcTAMU/s1600/IMG_20150228_100622.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h4 style="clear: both; text-align: left;">
Assembly</h4>
<div class="separator" style="clear: both; text-align: left;">
The bare board assembled (without VTX on bottom) is only 12 grams:</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiOuEArZHTuV_HEeCJ1pgJuF9WSXu6aW8zod75Y7x-qEKp5jIEBa9fEpMQkw6duAdz9SnIcAzmaeZkJKbMeEdf2Y4dT2kgNr-zU5FC-ov6zqrN9dBwNrCAWeEVWKC-N0xqfp-AcBpkpQMI/s1600/IMG_20150318_111202.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="248" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiOuEArZHTuV_HEeCJ1pgJuF9WSXu6aW8zod75Y7x-qEKp5jIEBa9fEpMQkw6duAdz9SnIcAzmaeZkJKbMeEdf2Y4dT2kgNr-zU5FC-ov6zqrN9dBwNrCAWeEVWKC-N0xqfp-AcBpkpQMI/s1600/IMG_20150318_111202.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And 41g ready to fly (without battery):</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj4oN8TDhUB-sud1Cr4bOHbd2u4m_Gd1jlfldKOx5pEIOz6F6WbRFjeodzwH0ApYMHv-iWhjcDtCCNBjZQMyRTkzAcFb4YM6o6ZF1LGxzXAyRMXVhu6Klif_elcXB6VaEDc5k7kJgsd8Fs/s1600/IMG_20150318_140350.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="251" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj4oN8TDhUB-sud1Cr4bOHbd2u4m_Gd1jlfldKOx5pEIOz6F6WbRFjeodzwH0ApYMHv-iWhjcDtCCNBjZQMyRTkzAcFb4YM6o6ZF1LGxzXAyRMXVhu6Klif_elcXB6VaEDc5k7kJgsd8Fs/s1600/IMG_20150318_140350.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both;">
And now I have a nice row of micros above my desk:</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjXzn09S7gSxN4HBliR-zmbUVOa131AKDKLpSItFshE0HQlxz3I8FLxt5YnfQsg8AuMWBpN3HQhKCHkJ_phXlYTuzermqNlCylSm9qUBoSKcY9AvKpMraRN5xfXbxrj2AQ4gv2qotxb4vs/s1600/IMG_20150318_144842.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="133" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjXzn09S7gSxN4HBliR-zmbUVOa131AKDKLpSItFshE0HQlxz3I8FLxt5YnfQsg8AuMWBpN3HQhKCHkJ_phXlYTuzermqNlCylSm9qUBoSKcY9AvKpMraRN5xfXbxrj2AQ4gv2qotxb4vs/s1600/IMG_20150318_144842.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h4 style="clear: both; text-align: left;">
Landing gear</h4>
<div class="separator" style="clear: both; text-align: left;">
One failure point is hitting the bottom of the motors and damaging them. I tried to design a more robust motor mount that protected them better and served as a landing gear:</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiafBzSBzdSm45FZvyQPDIxAs9DQtdvgENjkftWAld5ZJco5QzaW5mggZm656r7nfWlu3vw6OrDH5cGDdOyUivRi-zqRUleBLCWVkY94K9afEFpptiZy-Lhyphenhyphend6dvpouoBZ3Px5zZEY15wU/s1600/IMG_20150322_150734.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="195" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiafBzSBzdSm45FZvyQPDIxAs9DQtdvgENjkftWAld5ZJco5QzaW5mggZm656r7nfWlu3vw6OrDH5cGDdOyUivRi-zqRUleBLCWVkY94K9afEFpptiZy-Lhyphenhyphend6dvpouoBZ3Px5zZEY15wU/s1600/IMG_20150322_150734.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Unfortunately it coupled vibrations too strongly into the frame and resulted in bad attitude estimation (not hovering level). I went with the original design for the <a href="http://www.thingiverse.com/thing:704474">motor mount</a> and a <a href="http://www.thingiverse.com/thing:737486">landing cup </a>that clips onto the arm and protects things.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi3TXpPAXJOyOOXP0K414eXYkImOTtrfJoIjE-EOzQqzS4wY_8uyLedFkeZF9LpW-PdBqQjAjkjTInfmkN4nDIPqOPGqsge5cmFFtaD0nbqHJFtODpppS8OmJ2HquHpfF_eQi9JYCBgFgo/s1600/IMG_20150321_134052.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi3TXpPAXJOyOOXP0K414eXYkImOTtrfJoIjE-EOzQqzS4wY_8uyLedFkeZF9LpW-PdBqQjAjkjTInfmkN4nDIPqOPGqsge5cmFFtaD0nbqHJFtODpppS8OmJ2HquHpfF_eQi9JYCBgFgo/s1600/IMG_20150321_134052.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
They do pop off in crashes, but that's fine since it still saves any serious damage. I want to get my friend to try printing these in different materials - abs or flexible material - and see if it works any better.<br />
<br />
<h4 style="text-align: left;">
BOM</h4>
<div>
Here are the parts I'm using for my preferred assembly. You can either buy all the parts from multirotorsuperstore or in pieces.</div>
<div>
<ul style="text-align: left;">
<li>motors:</li>
<ul>
<li>20$ <a href="http://www.multirotorsuperstore.com/cl-0820-17-coreless-motor-set.html">http://www.multirotorsuperstore.com/cl-0820-17-coreless-motor-set.html</a></li>
<li>30$ <a href="http://micro-motor-warehouse.com/collections/all/products/cl-0820-17">micro-motor-warehouse.com/collections/all/products/cl-0820-17</a> precrimped with connectors</li>
</ul>
<li>props</li>
<ul>
<li>3$ for 4 colored: <a href="http://www.multirotorsuperstore.com/propellers/propellers-nylon/hubsan-prop-set.html">http://www.multirotorsuperstore.com/propellers/propellers-nylon/hubsan-prop-set.html</a></li>
<li>9$ for 20 clear: <a href="http://www.amazon.com/dp/B00RE5US38/ref=sr_ph?ie=UTF8&qid=1427170689&sr=1&keywords=hubsan+clear">http://www.amazon.com/dp/B00RE5US38/ref=sr_ph?ie=UTF8&qid=1427170689&sr=1&keywords=hubsan+clear</a></li>
</ul>
<li>camera</li>
<ul>
<li>30$ <a href="http://www.multirotorsuperstore.com/micro-600tvl-120-degree-camera.html">http://www.multirotorsuperstore.com/micro-600tvl-120-degree-camera.html</a> (nice FOV)</li>
<li>50$ <a href="http://www.getfpv.com/lumenier-cp-520-pico-520tvl-nano-camera.html">http://www.getfpv.com/lumenier-cp-520-pico-520tvl-nano-camera.html</a></li>
</ul>
<li>VTX module</li>
<ul>
<li>10$ <a href="http://www.banggood.com/FPV-5_8G-200mW-Wireless-Audio-Video-Transmitter-Module-TX5823-p-84780.html">http://www.banggood.com/FPV-5_8G-200mW-Wireless-Audio-Video-Transmitter-Module-TX5823-p-84780.html</a> (Boscam E band)</li>
<li>14$ <a href="http://www.rangevideo.com/58-ghz/57-tx5200m-58ghz-200mw-5v-transmitter-module.html">http://www.rangevideo.com/58-ghz/57-tx5200m-58ghz-200mw-5v-transmitter-module.html</a></li>
</ul>
<li>VTX antenna:</li>
<ul>
<li>RHCP 10$ http://www.fpvhobby.com/231-8-ghz-micro-cl-antenna-.html</li>
<li>LHCP 5$ http://www.banggood.com/FPV-5_8G-Circular-Polarized-LHCP-VTX-Antenna-p-961731.html</li>
</ul>
<li>battery:</li>
<ul>
<li>5$ <a href="http://www.multirotorsuperstore.com/battery/1s/1s-380mah-35c.html">http://www.multirotorsuperstore.com/battery/1s/1s-380mah-35c.html</a> (note these are 35C)</li>
<li>3.50$ <a href="http://hobbyking.com/hobbyking/store/__33260__Turnigy_nano_tech_750mah_1S_35_70C_Lipo_Pack_Fits_Nine_Eagles_Solo_Pro_180_US_Warehouse_.html">http://hobbyking.com/hobbyking/store/__33260__Turnigy_nano_tech_750mah_1S_35_70C_Lipo_Pack_Fits_Nine_Eagles_Solo_Pro_180_US_Warehouse_.html</a> (750mAh)</li>
</ul>
<li>charger and miscellaneous:</li>
<ul>
<li>charger: <a href="http://www.banggood.com/4-In-1-X4-Battery-Charger-For-Hubsan-X4-WLtoys-UDI-JXD-Syma-Quadcopter-p-933932.html">http://www.banggood.com/4-In-1-X4-Battery-Charger-For-Hubsan-X4-WLtoys-UDI-JXD-Syma-Quadcopter-p-933932.html</a></li>
<li><a href="http://www.amazon.com/gp/product/B007OXK330/ref=oh_aui_search_detailpage?ie=UTF8&psc=1">use this</a> for attaching. it is magical.</li>
</ul>
</ul>
<div>
<h4 style="text-align: left;">
Video</h4>
</div>
</div>
<div>
I'm really happy how it flies as well as the video quality (which the Dom V2 built in DVR doesn't do justice to). I started playing around in acro mode too and got some flips in, as well as a number of crashes. It takes abuse quite well, typically in a really bad crash just cracking the motor mount which takes about 2 minutes to replace.<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/123224072" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<b> (Update) </b>I also got telemetry on the Taranis via the TauLinkModule S.Port<br />
<br />
<br /></div>
<div>
<br /></div>
</div>
<blockquote class="instagram-media" data-instgrm-captioned="" data-instgrm-version="4" style="background: #FFF; border-radius: 3px; border: 0; box-shadow: 0 0 1px 0 rgba(0,0,0,0.5),0 1px 10px 0 rgba(0,0,0,0.15); margin: 1px; max-width: 658px; padding: 0; width: -webkit-calc(100% - 2px); width: 99.375%; width: calc(100% - 2px);">
<div style="padding: 8px;">
<div style="background: #F8F8F8; line-height: 0; margin-top: 40px; padding: 50% 0; text-align: center; width: 100%;">
<div style="background: url(data:image/png; display: block; height: 44px; margin: 0 auto -44px; position: relative; top: -22px; width: 44px;">
</div>
</div>
<div style="margin: 8px 0 0 0; padding: 0 4px;">
<a href="https://instagram.com/p/01deyhlqrA/" style="color: black; font-family: Arial,sans-serif; font-size: 14px; font-style: normal; font-weight: normal; line-height: 17px; text-decoration: none; word-wrap: break-word;" target="_top">Playing with #BrushedSparky Taranis telemetry. RSSI, voltage, current, flight mode, altitude, vario all on screen. Also speech warns of low voltage or RSSI, as well as signal disconnect. AndroidGCS is great but sometimes you just want minimal info.</a></div>
<div style="color: #c9c8cd; font-family: Arial,sans-serif; font-size: 14px; line-height: 17px; margin-bottom: 0; margin-top: 8px; overflow: hidden; padding: 8px 0 7px; text-align: center; text-overflow: ellipsis; white-space: nowrap;">
A video posted by peabody124 (@peabody124) on <time datetime="2015-03-30T02:36:52+00:00" style="font-family: Arial,sans-serif; font-size: 14px; line-height: 17px;">Mar 29, 2015 at 7:36pm PDT</time></div>
</div>
</blockquote>
<script async="" defer="" src="//platform.instagram.com/en_US/embeds.js"></script></div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com48tag:blogger.com,1999:blog-1759046512792102553.post-16167377256740557272015-02-28T13:56:00.001-08:002015-05-20T12:04:52.537-07:00BrushedSparky: Sparky2 + Microquads<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div class="separator" style="clear: both; text-align: left;">
<b>Update: see the next revision <a href="http://buildandcrash.blogspot.com/2015/03/brushedsparky-v02.html">here</a> </b></div>
<div class="separator" style="clear: both; text-align: left;">
<b>Also <a href="http://www.hobbiesfly.com/taulabs-sparky2-0.html">you can purchase Sparky2 here</a></b></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjj-fgBExafIFy8VOzvinDa0edwxbVvXGkBnTh-OkP2cZzgjuFRIqMeWJgMZ18PYyXxnwE0V5GN4vtBBba75JeX3XkaP2EpEk0pEBF7iEi5jSwv9CxTYVU9C95sZBOdWnMvtwL7Y5ticp0/s1600/DSC02202.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="279" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjj-fgBExafIFy8VOzvinDa0edwxbVvXGkBnTh-OkP2cZzgjuFRIqMeWJgMZ18PYyXxnwE0V5GN4vtBBba75JeX3XkaP2EpEk0pEBF7iEi5jSwv9CxTYVU9C95sZBOdWnMvtwL7Y5ticp0/s1600/DSC02202.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/120901200" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgrOH7BzNfgFd22RnOKL1Z9QZLS9Bx-ft_g648iRV_QggLC5iGJsAeUsAHJifdgohLTdE9Q2ys1tMAWPiMH01lWnwQKs_Ppg_cfnkHEPvR8YRSAnGD9vx6DHsjcs5L3I7BLa1mfo4TLuyY/s1600/DSC02210.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="209" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgrOH7BzNfgFd22RnOKL1Z9QZLS9Bx-ft_g648iRV_QggLC5iGJsAeUsAHJifdgohLTdE9Q2ys1tMAWPiMH01lWnwQKs_Ppg_cfnkHEPvR8YRSAnGD9vx6DHsjcs5L3I7BLa1mfo4TLuyY/s1600/DSC02210.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiV8kEikziyk4JkmZdIC-zuURklo5B8sjxV_n1JCa3Dzsdlio8Dfkq62f8zxVle2NUhoFrtLCN2W7f9YY8fE1n6dfdhZnkCWh101qq3ZRmuPMYMFdXd3Da7e6HJ_4EwnKhJBN4zVojR7tM/s1600/microbrushed2.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="236" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiV8kEikziyk4JkmZdIC-zuURklo5B8sjxV_n1JCa3Dzsdlio8Dfkq62f8zxVle2NUhoFrtLCN2W7f9YY8fE1n6dfdhZnkCWh101qq3ZRmuPMYMFdXd3Da7e6HJ_4EwnKhJBN4zVojR7tM/s1600/microbrushed2.jpg" width="320" /></a></div>
<br />
This is a new <a href="http://taulabs.org/">TauLabs</a> board I just finished making.<br />
<br />
I am now really into microquads for a number of reasons. They are much cheaper and relatively easier to build than full sized ones. They are great for testing things indoors while being quite safe. They make FPVing around a small space an adventure. Finally they are extremely easy to transport and then just quickly throw in the air.<br />
<br />
The last month or so I've been on an adventure to build the best microquad I could. The photo above is my latest and greatest creation. It is essentially the guts of <a href="http://taulabs.org/">TauLabs</a> <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky2</a> integrated into a single PCB with an integrated VTX and radio module on the bottom. This is a writeup of how I ended up there.<br />
<h3 style="text-align: left;">
Sparky2 based micros</h3>
<a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky2</a> has some transistor buffered outputs. I've previously demonstrated these to <a href="https://vimeo.com/105504442">control LEDs via PicoC to create a visual compass</a>. However, their real goal was to control brushed motors on a microquad. OsoGrande finally motivated me off my butt to actually try this the other day. We both got some of <a href="http://micro-motor-warehouse.com/collections/all/products/cl-0820-17">these brushed motors</a> that can draw a few amps and supposedly generate 40g of thrust each.<br />
<br />
Here is his:<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgRocrWx_gcAdscIqccGEalqXWEaD6y9CeddYsvAoe7vpt2VdULLN4L0MKuSbXbKagiprFyzcQRpZlW0tHKL0d6ApXZgDxta6x3-jq3-ZgfhUfJauF4bYC5XtHAycFL-RvY114NvFyqyAI/s1600/Photo+Feb+07,+9+46+25+AM.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="300" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgRocrWx_gcAdscIqccGEalqXWEaD6y9CeddYsvAoe7vpt2VdULLN4L0MKuSbXbKagiprFyzcQRpZlW0tHKL0d6ApXZgDxta6x3-jq3-ZgfhUfJauF4bYC5XtHAycFL-RvY114NvFyqyAI/s1600/Photo+Feb+07,+9+46+25+AM.jpg" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
and mine (actually with a frame of his):</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhqJqKqyH1d_3kDsvlSwIKNfyxyTFwPiKVgrjdr2v4hRIn9zb9__XgiOLT1G3lXMdyazP9_Le0aOStDhTn03dtrvR5Tu2dspAg8KIIKDoelWCoMMgiZL_qXnTRNvac23BJSMjNC8KOq9Es/s1600/IMG_20150212_184434.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="257" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhqJqKqyH1d_3kDsvlSwIKNfyxyTFwPiKVgrjdr2v4hRIn9zb9__XgiOLT1G3lXMdyazP9_Le0aOStDhTn03dtrvR5Tu2dspAg8KIIKDoelWCoMMgiZL_qXnTRNvac23BJSMjNC8KOq9Es/s1600/IMG_20150212_184434.jpg" width="320" /></a></div>
<h4 style="clear: both; text-align: left;">
I hate wiring</h4>
<div>
To get this ready for FPV, it is really annoying to add the 1S to 5V step up, not to mention dealing with the cables and adding a VTX. To make this easier, I made a board that takes care of some of the details (compatible with both Sparky1 and Sparky2)</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiDtZ3cYdK1qzls3EYreQcaiR2zagCnSM1XaOg0OjFFfaZIM4554jdoOmOt6dJQ-xsTEzKlCsVfXgQHIG2T0gHQCibAKhJvhK9AfG9tZssHNVwJ0QFM5PjGTuBz8O_Wq1jnMIRTvrZyW-k/s1600/BrushedAdapter.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="192" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiDtZ3cYdK1qzls3EYreQcaiR2zagCnSM1XaOg0OjFFfaZIM4554jdoOmOt6dJQ-xsTEzKlCsVfXgQHIG2T0gHQCibAKhJvhK9AfG9tZssHNVwJ0QFM5PjGTuBz8O_Wq1jnMIRTvrZyW-k/s1600/BrushedAdapter.png" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi7Fu-qEmziQLaHd0ojd7Gsm6fLemg44njiPCVgFfQhYvQ1HR6-_PHRpSUQKTZ8vXeMOde9u8EFDa3Z-HaJXGcVA6o5RFeieSw9edFuha1-YxLUpWQ9yNy3nc2h_1wIVD2TQIX6KucS64Q/s1600/IMG_20150228_105521.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="214" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi7Fu-qEmziQLaHd0ojd7Gsm6fLemg44njiPCVgFfQhYvQ1HR6-_PHRpSUQKTZ8vXeMOde9u8EFDa3Z-HaJXGcVA6o5RFeieSw9edFuha1-YxLUpWQ9yNy3nc2h_1wIVD2TQIX6KucS64Q/s1600/IMG_20150228_105521.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
<br /></div>
<div>
This adds the voltage boost, VTX, channel selection and connectors for standard motors. Before this even arrived, though, I was already on to a more fun idea (and want to redo it with 6 outputs for 3D printed hex's) ...<br />
<br />
About this time OsoGrande received a really nice little PCB frame that has pads for a Polulu step up and a VTX module for doing FPV as well as mounting holes compatible with Sparky2 (and AlienWii):<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjdEOtTVj6xMkXZ7f8E3HpPb4wTYGDg_qlXh_DVNYk8sZ1vpWtqT5MA24Jsjl7IN5ccLkAEtDvy8GVOxpQy1pWlAebJGhetBEO1gxnSHd1niSK-hF1IeYAhQDEup_4DEGJA1XcoGL_UxNU/s1600/IMG_20150223_165923.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjdEOtTVj6xMkXZ7f8E3HpPb4wTYGDg_qlXh_DVNYk8sZ1vpWtqT5MA24Jsjl7IN5ccLkAEtDvy8GVOxpQy1pWlAebJGhetBEO1gxnSHd1niSK-hF1IeYAhQDEup_4DEGJA1XcoGL_UxNU/s1600/IMG_20150223_165923.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
These were just too much fun to fly, but I really hated the wiring and ugliness of cobbling all these parts together.</div>
</div>
<h3 style="clear: both; text-align: left;">
BrushedSparky - A.K.A. Let's build a lot of these!</h3>
<div class="separator" style="clear: both; text-align: left;">
These tiny things are so much fun to fly, that I really wanted to make it easier to build them up and get rid of all the annoying wires and such. They are also great for micro FPV (see OsoGrande <a href="https://www.youtube.com/watch?v=Uv9lHI-XzzA">having fun</a>) but soldering up the wires for the camera seemed like a giant pain. </div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
I designed a board that should double as a frame. It's a little less than 100x100 mm. It is basically <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky2</a> has the RFM22b module for control and telemetry without an additional receiver, integrated 1S to 5V step up, <a href="http://www.rangevideo.com/58-ghz/10-tx5200m-58ghz-200mw-5v-transmitter-module.html">TX5200M VTX</a> and a full suite of sensors (so can do altitude hold and even navigation). It also has voltage monitoring and the digital to analog converter from Sparky2 goes to the audio input on the VTX so we should be able to send sounds to indicate low battery and such.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgyxY6um_EvJvYT4947vPgAuSeFgkebXp40hW3KyXnc_eYCjCzlpVMXYsTOO8Lo87s2SIWQl1JhoKAA25XZnaFF998GCQYNQADgFYMjUeK6jX9ZJEN3RWQu5mRQh17kUMRO5dZgjBljpeQ/s1600/Screen+Shot+2015-02-09+at+9.44.23+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="256" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgyxY6um_EvJvYT4947vPgAuSeFgkebXp40hW3KyXnc_eYCjCzlpVMXYsTOO8Lo87s2SIWQl1JhoKAA25XZnaFF998GCQYNQADgFYMjUeK6jX9ZJEN3RWQu5mRQh17kUMRO5dZgjBljpeQ/s1600/Screen+Shot+2015-02-09+at+9.44.23+PM.png" width="320" /></a></div>
</div>
</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Specs:</div>
<div class="separator" style="clear: both; text-align: center;">
</div>
<ul>
<li style="text-align: left;">Runs <a href="https://github.com/TauLabs/TauLabs/releases">TauLabs</a></li>
<li style="text-align: left;">STM32F4 process (168 MHz, floating point unit) so lots of horse power</li>
<li style="text-align: left;">MPU9250 gyro / accel /mag chip</li>
<li style="text-align: left;">MS5611 pressure sensor</li>
<li style="text-align: left;">RFM22b radio module (so hopefully this can be made OpenLRSNG compatible)</li>
<li style="text-align: left;">TX5200M VTX module with DIP switch for channel selection</li>
<li style="text-align: left;">4 6A buffered outputs</li>
</ul>
<br />
<h4 style="text-align: left;">
Soldering and testing</h4>
<div>
DragonCircuits was awesome enough to make these four layer boards quickly and at a great price! The boards looked as good as I hoped they might.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhtG3nNEVzVShwc_7JL0QpgBdcFxnlJ_jEn10vLUVeFkV6QyOWohaThyphenhyphen44NuoJ-7dhAkIPKCXQ3jsFkwE4BXd51-SC_joqMZ9r8saLc-hLoh1WkjJVNdyO1s2NycjzoIfTlRrihvhF1YCM/s1600/IMG_2394.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="281" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhtG3nNEVzVShwc_7JL0QpgBdcFxnlJ_jEn10vLUVeFkV6QyOWohaThyphenhyphen44NuoJ-7dhAkIPKCXQ3jsFkwE4BXd51-SC_joqMZ9r8saLc-hLoh1WkjJVNdyO1s2NycjzoIfTlRrihvhF1YCM/s1600/IMG_2394.jpg" width="640" /></a></div>
<br />
Here is one fully populated:</div>
</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEihvfbho3BzqgXXGa5ezLr_bvcylDDXDyklO-HnJhtDcXhWe2tgtTnECIATluWLDU53rq4OV5DmbU5MTgKx-n7FK-BiMx8y3W4BpINRCKoJySyHHuuH0WNO48iKFbTr-SuElM_E4-3rvlk/s1600/IMG_20150223_110448.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="288" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEihvfbho3BzqgXXGa5ezLr_bvcylDDXDyklO-HnJhtDcXhWe2tgtTnECIATluWLDU53rq4OV5DmbU5MTgKx-n7FK-BiMx8y3W4BpINRCKoJySyHHuuH0WNO48iKFbTr-SuElM_E4-3rvlk/s1600/IMG_20150223_110448.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Here are the motor mount files I designed:</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwb_D7KNEPaok1DnUtIfRL19mPlW5U6y2qdOuyZGcGIZsZ7VuSCQiuGa3ag_25E0hOSWlTNaHfzp61yInVBshX7Cy2WkgBJ_bjJOovj8M5mpceebBARJ49yu9tV7rCI1U7MHgm-kgeddA/s1600/MicroQuadMount_pins_v0.2_preview_featured.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwb_D7KNEPaok1DnUtIfRL19mPlW5U6y2qdOuyZGcGIZsZ7VuSCQiuGa3ag_25E0hOSWlTNaHfzp61yInVBshX7Cy2WkgBJ_bjJOovj8M5mpceebBARJ49yu9tV7rCI1U7MHgm-kgeddA/s1600/MicroQuadMount_pins_v0.2_preview_featured.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
To save weight I used pegs on the mount instead of holes with hardware. This seems to work quite well, although I add a drop of loctite to keep them in place. I uploaded the files to <a href="http://www.thingiverse.com/thing:704474">thingiverse</a>.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
A few things I already want to change</div>
<div class="separator" style="clear: both; text-align: left;">
</div>
<ul style="text-align: left;">
<li>Fix some small mistakes I made :)</li>
<li>Adding holes for the camera and motor connections to make it easy for the headers to be optional.</li>
<li>Add current sensing</li>
<li>The buzzer I used is really not loud enough so I'll be looking for another one of those. </li>
<li>Finally I really need to add a power switch for the VTX and camera so you can have it off when it isn't desired.</li>
<li>VTX channel selection routed to the F405 to avoid carrying the DIP switch</li>
<li>Few other fun surprises</li>
</ul>
<br />
<div class="separator" style="clear: both; text-align: left;">
Here is one that is populated to be a bit lighter. I'm soldering the motor wires directly to the pads and used a solder bridge to select the video channel instead of using the dip switch. It comes in at 43g.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiGO1inkCPE4p6b6VfKIK3Ky4y-Npwe1DMZnwmOEjVWho4kOgDUZljG-Fmya0_gtUl_Be9N8kD2N5ZPCEwpXUUp_U638RZLB-E5qqAK7wrfAQMKEdiLzO8Uv4RxrfDMIx7bY1SI5VgNiK0/s1600/microbrushed.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="236" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiGO1inkCPE4p6b6VfKIK3Ky4y-Npwe1DMZnwmOEjVWho4kOgDUZljG-Fmya0_gtUl_Be9N8kD2N5ZPCEwpXUUp_U638RZLB-E5qqAK7wrfAQMKEdiLzO8Uv4RxrfDMIx7bY1SI5VgNiK0/s1600/microbrushed.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Here is an image of the bottom. You can see the radio module in the middle (RFM22b) and the VTX a bit further forward. The velcro on the VTX module is for when I want to carry a keychain camera.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi2qLNnzJs5Gzj-j3Z2njFD-KDXmG5ktZoMEE80NsE_1Kaoa7cNm8eM7-CIuz1hiFa2E1YSCkt2ZZ4Y6AdfGneYie38VlBc4g89qHO6QuXetTxRgktjnI5DTkd0ckd9dVh4tWhhDJ_aFeg/s1600/IMG_20150228_184516.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi2qLNnzJs5Gzj-j3Z2njFD-KDXmG5ktZoMEE80NsE_1Kaoa7cNm8eM7-CIuz1hiFa2E1YSCkt2ZZ4Y6AdfGneYie38VlBc4g89qHO6QuXetTxRgktjnI5DTkd0ckd9dVh4tWhhDJ_aFeg/s1600/IMG_20150228_184516.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
They are small enough I kept losing them, until I realized a little velcro could easily secure them over my desk:</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjnMxsHPYNWsVaWXYEQ5sbM-7dbDoeCFZeBfyYC31cXycNW3LfJYDLT2r7N61l36keW9D16xy80IFl3HlsGHePf9UTRn4-_V0tXVDQROBUAsgQRHN7g7YMrnSJQW1covo5xgluu-qivSQc/s1600/IMG_20150228_122712.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="225" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjnMxsHPYNWsVaWXYEQ5sbM-7dbDoeCFZeBfyYC31cXycNW3LfJYDLT2r7N61l36keW9D16xy80IFl3HlsGHePf9UTRn4-_V0tXVDQROBUAsgQRHN7g7YMrnSJQW1covo5xgluu-qivSQc/s1600/IMG_20150228_122712.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="clear: both; text-align: left;">
Control Module</h3>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
Since every gram counts on these things, I'd prefer to use RFM22b control instead of a satellite. I've already been using <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">TauLink</a> for this but it is a annoying to <a href="https://instagram.com/p/u3S-7elqhk/">jury rig into a JR socket with a bluetooth relay module</a>. I ended up designing a module that should fit into a JR socket and also has a bluetooth module to relay telemetry. This should allow me connect android (or even iphone is someone wrote code) to the quad without any additional wires. This uses a HM-10 bluetooth low energy module (which is actually compatible with iPhone as well) and the RFM22b module used on Sparky2 and TauLink.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi_m2ACpSH0R_-mospV6a_DKOO2tibH4BYDFQyMHmA-3xYReF0_y6g4NZIZJ81VJSRMW4kTEXXk6t4-ubEkDNrW77GS43W4ZJmlzRLFKJI2xW3Vi55twchX19Ci232wuNrD0rrPe4B_0iM/s1600/Screen+Shot+2015-02-13+at+11.34.28+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="291" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi_m2ACpSH0R_-mospV6a_DKOO2tibH4BYDFQyMHmA-3xYReF0_y6g4NZIZJ81VJSRMW4kTEXXk6t4-ubEkDNrW77GS43W4ZJmlzRLFKJI2xW3Vi55twchX19Ci232wuNrD0rrPe4B_0iM/s1600/Screen+Shot+2015-02-13+at+11.34.28+AM.png" width="320" /></a></div>
<br />
It plugs in quite well and fits into a JR socket easily. I'll probably make it a touch bigger just to give a few more mounting points for stability, but it fits well as it is. Plugs in nicely and smoothly into the socket pins.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjw9_vPzwcrgUPVmVfJSeYieZixZoAFjKn_wwBwTxIH6FrSkjgo416EwSCEqEImUfzI5Q0gqlRfs6-kLhaRsn7Y442L93fZevi-3y2pRDw1fCO6Q-nOoM3A0xHJNOQ3J_3ySiu9i8b0HwU/s1600/taulinkmodule.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="248" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjw9_vPzwcrgUPVmVfJSeYieZixZoAFjKn_wwBwTxIH6FrSkjgo416EwSCEqEImUfzI5Q0gqlRfs6-kLhaRsn7Y442L93fZevi-3y2pRDw1fCO6Q-nOoM3A0xHJNOQ3J_3ySiu9i8b0HwU/s1600/taulinkmodule.jpg" width="320" /></a></div>
<div>
<br /></div>
<div>
And of course the important thing is that it of course connects well to the quad for telemetry and PPM control. It was a bit of work to add support for this type of bluetooth low energy module to the androidgcs but it is also working. Gives me nice audio alerts for things like a low battery voltage and verbally tells me the flight mode.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjjGNakE1Wr_lmU6zYkUsfsBN1t6_GaGBKNArX_IKLuqCZoncnskVcU-GToj0iF7XzHr2-O9jmLN0Z8VOxxM3rv4DnqCid042lXSkvZCFawcyNH7ratjdQS6LBls0bQxJtitjCAbrPSuDo/s1600/20150228_013105_075.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="293" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjjGNakE1Wr_lmU6zYkUsfsBN1t6_GaGBKNArX_IKLuqCZoncnskVcU-GToj0iF7XzHr2-O9jmLN0Z8VOxxM3rv4DnqCid042lXSkvZCFawcyNH7ratjdQS6LBls0bQxJtitjCAbrPSuDo/s1600/20150228_013105_075.jpg" width="320" /></a></div>
<div>
<br /></div>
<div>
And a quick 3D printed mount to secure my phone over the transmitter to make it easy to use at the field:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhLmj1FtQQtO00bDVaoUwkLQKL8U66BKloKCbZczDARLrBmBiFvn54xsBmBoTSv9luvZtN3mMRFt5R5QJimFs_xULEdDVkIy_7kcgpYiM-DGAOweolUAG4mZv96IVhBaXV2Ze0ikhYyQL0/s1600/Screen+Shot+2015-02-28+at+1.59.53+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="200" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhLmj1FtQQtO00bDVaoUwkLQKL8U66BKloKCbZczDARLrBmBiFvn54xsBmBoTSv9luvZtN3mMRFt5R5QJimFs_xULEdDVkIy_7kcgpYiM-DGAOweolUAG4mZv96IVhBaXV2Ze0ikhYyQL0/s1600/Screen+Shot+2015-02-28+at+1.59.53+PM.png" width="192" /></a></div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjj-fgBExafIFy8VOzvinDa0edwxbVvXGkBnTh-OkP2cZzgjuFRIqMeWJgMZ18PYyXxnwE0V5GN4vtBBba75JeX3XkaP2EpEk0pEBF7iEi5jSwv9CxTYVU9C95sZBOdWnMvtwL7Y5ticp0/s1600/DSC02202.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="279" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjj-fgBExafIFy8VOzvinDa0edwxbVvXGkBnTh-OkP2cZzgjuFRIqMeWJgMZ18PYyXxnwE0V5GN4vtBBba75JeX3XkaP2EpEk0pEBF7iEi5jSwv9CxTYVU9C95sZBOdWnMvtwL7Y5ticp0/s1600/DSC02202.jpg" width="320" /></a></div>
<div>
<br /></div>
<div>
One thing that is annoying right now. The BT LE module doesn't work as simply as standard serial modules so I'll have to see if it is possible to relay to computer. This might be a reason to change modules, although with laptop it's easy enough to plug in USB cable since I'm normally inside rather than in field. This might not apply as well for everyone else, though.</div>
<div>
<br /></div>
<div>
The other important goal of this module is actually to pump information back into the Taranis, so even without a tablet or computer you can see things like battery voltage, RSSI and LinkQuality. I'll update more about this later.</div>
<h3 style="text-align: left;">
Flight testing</h3>
<div style="text-align: left;">
Overall I'm really happy with how they fly. The VTX module gets fairly hot (as do the motors) but so far nothing too much so. The video is pretty good, although not great. I think my receiver module is not on the same frequency bands as this module (it is on Boscam A frequencies and I think my stuff is on ImmersionRC frequencies). Alternatively, maybe a small circularly polarized VTX antenna will help since my breaking up seems to be at strong angles.</div>
<div style="text-align: left;">
<br />
With a 750mAh battery it will hover for around 5 minutes at about half throttle. It weighs 65g in this configuration.<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjqsy_t35B3yc5wyM2Z-WhvSleYHlL13idxF4wZ5vn22irBSjjoxXNZIdZUD3DOV5tRuv1-FFn-F2PRCK1cpPfJ0-oluh7C0fnegqnTKQp_XoRni0gZ63qAIp3KLp6uaHydc_p3iiozYGU/s1600/IMG_20150228_165034.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjqsy_t35B3yc5wyM2Z-WhvSleYHlL13idxF4wZ5vn22irBSjjoxXNZIdZUD3DOV5tRuv1-FFn-F2PRCK1cpPfJ0-oluh7C0fnegqnTKQp_XoRni0gZ63qAIp3KLp6uaHydc_p3iiozYGU/s1600/IMG_20150228_165034.jpg" width="320" /></a></div>
<br /></div>
<div style="text-align: left;">
Of course, here is the video (same as above):<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/120901200" webkitallowfullscreen="" width="500"></iframe></div>
<div>
<br />
Here is OsoGrande out testing his using some people as obstacles:<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="315" src="https://www.youtube.com/embed/YUCvEafHjSA" width="560"></iframe>
</div>
<div style="text-align: center;">
<br /></div>
It will also fly with a keychain camera attached to the bottom, but that adds another 19g and<br />
takes most of the spare thrust so I don't really enjoy flying like this. Ground side recording for now it is.</div>
</div>
<h3 style="text-align: left;">
Future fun</h3>
<div>
<br />
<ul style="text-align: left;">
<li>The Pico camera I'm using right now is a bit heavier than I'd like, so I want to try out <a href="http://www.multirotorsuperstore.com/fpv/fpv-cameras/micro-600tvl-120-degree-camera.html">this one</a> from multirotorsuperstore.com that also has a wider FOV for exploring the furniture <b>(update: tried it and I like it!)</b>:</li>
</ul>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgdKMz1-aEhfFr3TLAuf7iUMNLxCLYr1zrotiZGnogheUkUrQm5goU0vML9c-s7JS5BZlV71TfHvfiWiQNsdFmg4fnKCO8h4vcXBTOwHCpUTa2zOdZEZUsHOEuudYZKpU1C8KrBqjMSD3I/s1600/IMG_20150228_122745.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="306" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgdKMz1-aEhfFr3TLAuf7iUMNLxCLYr1zrotiZGnogheUkUrQm5goU0vML9c-s7JS5BZlV71TfHvfiWiQNsdFmg4fnKCO8h4vcXBTOwHCpUTa2zOdZEZUsHOEuudYZKpU1C8KrBqjMSD3I/s1600/IMG_20150228_122745.jpg" width="320" /></a></div>
<br />
<br />
<ul style="text-align: left;">
<li>I also wanted to see if this would behave well for navigation, so spun it a few times while logging and threw the data into the python calibration script:<br /><br /><div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh5O5C7siCiIkU70DReNZREVulEonOfkV8oEmStPM_6tj5bt9vUZKjpZc4ZZQYpCtT-IkeC_4oj9dIKXzn6sZHBLVMfASxn7GSm49-6tnSny9bGW5-X9QPpFuxCzzD8s5ukyGlrNj9UA-U/s1600/Screen+Shot+2015-02-07+at+9.08.14+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em; text-align: center;"><img border="0" height="309" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh5O5C7siCiIkU70DReNZREVulEonOfkV8oEmStPM_6tj5bt9vUZKjpZc4ZZQYpCtT-IkeC_4oj9dIKXzn6sZHBLVMfASxn7GSm49-6tnSny9bGW5-X9QPpFuxCzzD8s5ukyGlrNj9UA-U/s1600/Screen+Shot+2015-02-07+at+9.08.14+AM.png" width="320" /></a></div>
<div style="text-align: right;">
</div>
<br />The nice round circle shows that the magnetometer is a beautiful round circle, so with a GPS it should work great for navigation.</li>
<li>Get Taranis input straight from telemetry with the TauLinkModule so basic things (e.g. RSSI, Battery voltage) are shown on transmitter without even needing phone or tablet.</li>
<li>I really need to join up with OsoGrande (who I made one of these for as well) and do some FPV racing in the garage near him...</li>
</ul>
<h3 style="text-align: left;">
Fun for you too?</h3>
<div>
Also since I know the inevitable torrent of questions about this is going to be "where can I get one", I'm working with someone to try and get them manufactured. In the mean time I'll likely make a few for friends and developers for testing purposes, but not too many. Keep an eye on my Instagram/twitter account and I'm sure you'll know not long after I do.</div>
</div>
<div>
<br /></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com48tag:blogger.com,1999:blog-1759046512792102553.post-56390794613362331982015-01-31T23:06:00.000-08:002015-02-01T15:28:24.758-08:00OneShot125: Quantitative Testing<div dir="ltr" style="text-align: left;" trbidi="on">
<b>Note: this original spoke of the sensor rate being 666. However, this was a mistake and the sensor rates were 500 Hz and 1000 Hz.</b><br />
<br />
There has been a lot of talk about OneShot125 mode for ESCs and how much better you can tune your quadcopter with it. Briefly, this is a mode that uses a pulse width of 125-250 µs instead of the typical 1000-2000 µs. This shorter pulse width allows a higher update rate (up to 2khz). In addition, the recommendation is to update the output as soon as you calculate a new value. This improves the latency of sensor to ESCs in two ways: the synchronous update reduces the latency due to two independent loops and the shorter pulse duration saves another 1.5ms waiting for the falling edge of the pulse. With an update rate of 400 Hz on the PWM outputs that latency has a worse case of 2.5 ms so ultimately you are talking about 4ms latency reduction.<br />
<br />
It sounds somewhat unlikely that such a small time delay would make a difference, but at the same time the ESC latency is the ultimate performance bottle neck for quadcopters. With ESC response times getting into the 10-20s of ms, this communication latency can become an appreciable component.<br />
<br />
Back in December ernieieft wrote Tau Labs <a href="https://github.com/TauLabs/TauLabs/pull/1424">support for it</a> and with autotuning got higher PIDs and felt like it was quite locked in. Here you can see the outputs from the four channels as well as the interrupt from the MPU9250 on Sparky2. This shows that each time there is a sensor update, shortly after it there is a pulse on the output channels (synchronous updates).<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEizEM006nDhchQRM2qMbBwWgZO8kUNu3ozaQVjNCvvvYUGtY1QHFgWIZVUCClUapZbjKUwiiLkxaC1SCkNyoaYsSu6JL4zDJZusMMfyERZDHzc3AYY7iIdZiRlYVwmT4OoFV17T4jZ0NU8/s1600/Screen+Shot+2015-02-01+at+11.24.48+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEizEM006nDhchQRM2qMbBwWgZO8kUNu3ozaQVjNCvvvYUGtY1QHFgWIZVUCClUapZbjKUwiiLkxaC1SCkNyoaYsSu6JL4zDJZusMMfyERZDHzc3AYY7iIdZiRlYVwmT4OoFV17T4jZ0NU8/s1600/Screen+Shot+2015-02-01+at+11.24.48+AM.png" height="65" width="320" /></a></div>
<br />
Zooming in, we can see what the latency is from the MPU9250 indicating a sample is ready to actually completing the pulse, and it is about 300 µs. Much better than the worst case 4 ms described above. This is with a short output pulse so in reality the time could go as high as 450 µs.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhws_vM7hLq70uS84vpOTPqzBiPAvuGi9oJbJyRdi5O5gqjUYs7qRRYP-8gww7VvuKRr2Hw4tBMa51NbmSA6KSD0aYFo05hJpm4pIkRYjONnt9_eM1WuEQBvcWIgjcrVWDaHUa7avaHj1o/s1600/Screen+Shot+2015-02-01+at+11.25.27+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhws_vM7hLq70uS84vpOTPqzBiPAvuGi9oJbJyRdi5O5gqjUYs7qRRYP-8gww7VvuKRr2Hw4tBMa51NbmSA6KSD0aYFo05hJpm4pIkRYjONnt9_eM1WuEQBvcWIgjcrVWDaHUa7avaHj1o/s1600/Screen+Shot+2015-02-01+at+11.25.27+AM.png" height="118" width="320" /></a></div>
<br />
However, I wanted to quantitatively compare how much specifically OneShot125 mode really makes a difference. Luckily, we have our <a href="http://forum.taulabs.org/viewtopic.php?f=17&t=99">autotuning algorithm</a> which actually allows monitoring the time constant of the delay from a change in the output to a change in the gyros.<br />
<br />
<h2 style="text-align: left;">
Normal PWM mode</h2>
So first I ran autotuning with <a href="http://buildandcrash.blogspot.com/2014/11/seeing-spark-sparky2-and-sparkybgc-quad.html">Seeing Spark</a> and Sparky2 using KISS ESCs in traditional mode. This is with the sensor running at the default rate for Sparky2 (500 Hz).<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/118383414" webkitallowfullscreen="" width="500"></iframe> </div>
<div style="text-align: center;">
<br /></div>
After three repeats, this is what I got:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj20ymawPWyTDSNOWn3dMhSAxsJj0QgF2cry5c64f1YxX_FLrFFjxqaKjhhxpZnxWrN5vL5pSISd2xgDxFpWHnS1i1ppR-giNLz_lGA26c8WzyJO46DgSBOLPSYoIHkHBoz1pu_nLdW_ic/s1600/Screen+Shot+2015-01-31+at+9.42.49+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj20ymawPWyTDSNOWn3dMhSAxsJj0QgF2cry5c64f1YxX_FLrFFjxqaKjhhxpZnxWrN5vL5pSISd2xgDxFpWHnS1i1ppR-giNLz_lGA26c8WzyJO46DgSBOLPSYoIHkHBoz1pu_nLdW_ic/s1600/Screen+Shot+2015-01-31+at+9.42.49+PM.png" height="61" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhSjOzHtwzosfnUNcr97se7gP5DX4PsxpeQio_BV9B8Ad4ojNJa4Xzi9CBC9WxhHIft20QNMOWqvORcWMyIqrT3lLX681c1TKwTyLqkj80qbjSFZFIx64KQYw-nunkOaeR3v9DcSHXGP6k/s1600/Screen+Shot+2015-01-31+at+9.44.24+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhSjOzHtwzosfnUNcr97se7gP5DX4PsxpeQio_BV9B8Ad4ojNJa4Xzi9CBC9WxhHIft20QNMOWqvORcWMyIqrT3lLX681c1TKwTyLqkj80qbjSFZFIx64KQYw-nunkOaeR3v9DcSHXGP6k/s1600/Screen+Shot+2015-01-31+at+9.44.24+PM.png" height="60" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCXSNYknYT6i-fXxYV0kQTEdIussNLIm3MrQf2Xi4G5o6REkcAscszjHVMjHQCOzK8VE8smb6n_x3nRwZn0dZjC9gLe3yooxPttZWBsEFKq4m5X8GZgYEfk-68BCj6werAS1IC8nnD2vk/s1600/Screen+Shot+2015-01-31+at+9.46.29+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCXSNYknYT6i-fXxYV0kQTEdIussNLIm3MrQf2Xi4G5o6REkcAscszjHVMjHQCOzK8VE8smb6n_x3nRwZn0dZjC9gLe3yooxPttZWBsEFKq4m5X8GZgYEfk-68BCj6werAS1IC8nnD2vk/s1600/Screen+Shot+2015-01-31+at+9.46.29+PM.png" height="61" width="320" /></a></div>
<br />
<h2 style="text-align: left;">
OneShot125</h2>
<div>
Then I cracked SeeingSpark open and soldered the <a href="http://ultraesc.de/downloads/KISS%20ESC%20Manual%20EN%20v01.pdf">JP1 bridge</a> to enable OneShot mode.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi7Ysa4yfIRRliVS17FtV3XufsnGObqPvrJVvLCsd9T4N2eBkTsgkF_klejv8ikor6PC5Q_2j8HFMuRPayXalE7JVlEimWcYrbwcaBlwRX4NXmhoWQYjm9fqQJMnTRK_uhyphenhyphenN3aZ3-vCAmE/s1600/20150131_221545_677.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi7Ysa4yfIRRliVS17FtV3XufsnGObqPvrJVvLCsd9T4N2eBkTsgkF_klejv8ikor6PC5Q_2j8HFMuRPayXalE7JVlEimWcYrbwcaBlwRX4NXmhoWQYjm9fqQJMnTRK_uhyphenhyphenN3aZ3-vCAmE/s1600/20150131_221545_677.jpg" height="243" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjLMUYG8-nqvH5LFN6JQ7GryJfQ_j3iklR2W_4uk4EFHON9LlJeIZ5zyt8OE4MsroJa3wAKBAOqMFBgRJ_nIVze7H8fSCNuttKBUeBWgyMFYHmXVdnHA0dU6qWIG68yrubFP0gh74ehzSA/s1600/20150131_221830_695.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjLMUYG8-nqvH5LFN6JQ7GryJfQ_j3iklR2W_4uk4EFHON9LlJeIZ5zyt8OE4MsroJa3wAKBAOqMFBgRJ_nIVze7H8fSCNuttKBUeBWgyMFYHmXVdnHA0dU6qWIG68yrubFP0gh74ehzSA/s1600/20150131_221830_695.jpg" height="219" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiF1yMRHq8PFwLVdaZA1dM2unUUrEq7_bvwjNY10l7TOf8PSHXhggm3RvtdvD21BONpnzGUcqnaEiYXqiQ2RfNqaNlrtuiHeqMUhddkhyphenhyphenEGMCmuDysIYs71ssq5HNU6BkKaSJWy0Zlz_Zg/s1600/20150131_222056_339.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiF1yMRHq8PFwLVdaZA1dM2unUUrEq7_bvwjNY10l7TOf8PSHXhggm3RvtdvD21BONpnzGUcqnaEiYXqiQ2RfNqaNlrtuiHeqMUhddkhyphenhyphenEGMCmuDysIYs71ssq5HNU6BkKaSJWy0Zlz_Zg/s1600/20150131_222056_339.jpg" height="245" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<i>Note: per request I have put the files to make this <a href="https://oshpark.com/shared_projects/5MMpnB1l">power distro board on OSHPark</a>. I'll try and make a BOM and assembly guidelines and upload that soon.</i></div>
<div>
<br />
Here you can see the outputs running at 500 Hz synchronously to the sensor.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhwcCFW1zsbPX7krojRG_gjEZZe48wJ6-SPi9bwCmJsl4_WJjgkTPgK10M2Dw1jPAR56z4fEt6A-at4omk-oNIwD1pndYKcuKCWATCcV6zCk60X7PdHTWR0Z0hRX1zCkH08D5ll9QoknKE/s1600/Screen+Shot+2015-02-01+at+11.23.14+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhwcCFW1zsbPX7krojRG_gjEZZe48wJ6-SPi9bwCmJsl4_WJjgkTPgK10M2Dw1jPAR56z4fEt6A-at4omk-oNIwD1pndYKcuKCWATCcV6zCk60X7PdHTWR0Z0hRX1zCkH08D5ll9QoknKE/s1600/Screen+Shot+2015-02-01+at+11.23.14+AM.png" height="66" width="320" /></a></div>
<br /></div>
<div>
Then popped in a fresh battery, and did a few more sessions of autotuning.<br />
<br /></div>
<h2 style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/118384283" webkitallowfullscreen="" width="500"></iframe></h2>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjTB3TYSEcX2WKg4gh-AHU3d4w3Mad-Hhsg6MJ-65nTrVpgKQj5pOaRTaZWJ0SIy6kzhRHG-C1R8ck0iT2NAs-IEDafVhrYmKp1_kbevYyHepqLiZv8EguF2hzRzwc-D_-4awCgWYlw2jA/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.40.31+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjTB3TYSEcX2WKg4gh-AHU3d4w3Mad-Hhsg6MJ-65nTrVpgKQj5pOaRTaZWJ0SIy6kzhRHG-C1R8ck0iT2NAs-IEDafVhrYmKp1_kbevYyHepqLiZv8EguF2hzRzwc-D_-4awCgWYlw2jA/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.40.31+PM.png" height="88" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhp84hAjG8khx__YwKDpa8ON8nuxBlN4aSDywj8OM7YUfgN1ag_sYw0GsgmqBnQfkyYt9vDCVTR2dYNm6hghmGMbbgMrMdv8b_Wii7Vk0GqzgqATZVEskXMwpDL4nO-OD04K9Nv1DDFbuA/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.55.16+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhp84hAjG8khx__YwKDpa8ON8nuxBlN4aSDywj8OM7YUfgN1ag_sYw0GsgmqBnQfkyYt9vDCVTR2dYNm6hghmGMbbgMrMdv8b_Wii7Vk0GqzgqATZVEskXMwpDL4nO-OD04K9Nv1DDFbuA/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.55.16+PM.png" height="57" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCwfrdYvnfcvcbcIA3UR704ztArKpcKoLlHpiSes8yYUmhcF_b8HeinYJJN9eCQIkER-tbdC_rP6Ac2Rjli2j2XFrXy-GAXyhprv3WLTD1Z1Y6mj6maSmIuUung2jZz2NDiyXSU3-HYKM/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.56.59+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCwfrdYvnfcvcbcIA3UR704ztArKpcKoLlHpiSes8yYUmhcF_b8HeinYJJN9eCQIkER-tbdC_rP6Ac2Rjli2j2XFrXy-GAXyhprv3WLTD1Z1Y6mj6maSmIuUung2jZz2NDiyXSU3-HYKM/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.56.59+PM.png" height="58" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhglFMthHLxu00HoU5_WaAjOU_v-aMqy8PG0dkxuEwQiqy6uadUStu5l6NtHDFa0fCJ11mJ8rlFzNxNiNy-gQewOI0La_rPZGyiwfTBVOIvJQeWO3gJeWUrVGh2Jx05YWI7tFNVD7XVlto/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.58.26+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhglFMthHLxu00HoU5_WaAjOU_v-aMqy8PG0dkxuEwQiqy6uadUStu5l6NtHDFa0fCJ11mJ8rlFzNxNiNy-gQewOI0La_rPZGyiwfTBVOIvJQeWO3gJeWUrVGh2Jx05YWI7tFNVD7XVlto/s1600/oneshot-666-Screen+Shot+2015-01-31+at+10.58.26+PM.png" height="59" width="320" /></a></div>
<div>
<br /></div>
<h2 style="text-align: left;">
OneShot125 - 1000 Hz sensor rate</h2>
<div>
I also wanted to see if increasing the sensor rate to further reduce the latency would cause more improvement, so I set it to 1 Khz.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjfF4yP3JG2C9BcF3-UYZpRV2-UYNG9RQ_0MG_Cvy_LPnFuXbpEtCj9Bf4lMnSPMNL0EvmQdi5jnhlsfZslHYncOFQmGEcRHRuSvJgekxoMy0Y_BqgmwlDoeTYnpp4nbPLWHbIFZ-whGvI/s1600/Screen+Shot+2015-02-01+at+11.06.12+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjfF4yP3JG2C9BcF3-UYZpRV2-UYNG9RQ_0MG_Cvy_LPnFuXbpEtCj9Bf4lMnSPMNL0EvmQdi5jnhlsfZslHYncOFQmGEcRHRuSvJgekxoMy0Y_BqgmwlDoeTYnpp4nbPLWHbIFZ-whGvI/s1600/Screen+Shot+2015-02-01+at+11.06.12+AM.png" height="84" width="320" /></a></div>
<br />
and ran another three rounds of autotuning.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlWWtt1ddaUnsTqIxFTYh_XjeMni5eygKeD_bgoh-6UxJqeF-NQRrCbUHGNeLKhIaqoXN7xXjG5q3R7Ad7z-vWU7XipIU8kEdB6YLjDc_0_XwGR1_us94IWYYPKUIMUEgeE0d_DU9cgCg/s1600/oneshot-1000-Screen+Shot+2015-01-31+at+10.46.00+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlWWtt1ddaUnsTqIxFTYh_XjeMni5eygKeD_bgoh-6UxJqeF-NQRrCbUHGNeLKhIaqoXN7xXjG5q3R7Ad7z-vWU7XipIU8kEdB6YLjDc_0_XwGR1_us94IWYYPKUIMUEgeE0d_DU9cgCg/s1600/oneshot-1000-Screen+Shot+2015-01-31+at+10.46.00+PM.png" height="86" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEisOFelyWSYX294DiQC3xjdshF0f3LhEEp8a0kohnL-zuAd2TStiqLzrdCFdHyNBd5zsFeFgmfbdUrvyLdXjKSUhe8KWWKwv53Kb109o1DF27XPM5ObuYoYGbOjfJYSfvNKMVQbP9u8gjI/s1600/oneshot-1000-Screen+Shot+2015-01-31+at+10.47.31+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEisOFelyWSYX294DiQC3xjdshF0f3LhEEp8a0kohnL-zuAd2TStiqLzrdCFdHyNBd5zsFeFgmfbdUrvyLdXjKSUhe8KWWKwv53Kb109o1DF27XPM5ObuYoYGbOjfJYSfvNKMVQbP9u8gjI/s1600/oneshot-1000-Screen+Shot+2015-01-31+at+10.47.31+PM.png" height="86" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgk7wWiDJ2LdGN3rQ3YbWoabtgU9oBBanD_s7K_wF4VOZwwmJM9Zo-yH1akhuD6vACA-_8eEJJzPVgiTa-2A-9gwg-Ij7AjU8vhLX0IiNasdpSx4-_nKs2jvl_BEgBYIouwFnsMoPHiLrk/s1600/oneshot-1000-Screen+Shot+2015-01-31+at+10.49.47+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgk7wWiDJ2LdGN3rQ3YbWoabtgU9oBBanD_s7K_wF4VOZwwmJM9Zo-yH1akhuD6vACA-_8eEJJzPVgiTa-2A-9gwg-Ij7AjU8vhLX0IiNasdpSx4-_nKs2jvl_BEgBYIouwFnsMoPHiLrk/s1600/oneshot-1000-Screen+Shot+2015-01-31+at+10.49.47+PM.png" height="86" width="320" /></a></div>
<div>
<br />
<h2 style="text-align: left;">
Statistics</h2>
</div>
<div>
So of course the punchline. Is there a significant difference between traditional PWM and OneShot mode as measured by the time constant of the response? Yes. Anova shows p < 0.01 for an effect of output type:</div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi5P7ro_TtpIwobiivPBH0GXsED4hCyKm9pFc4q_ZdrGjJ3qh-qKNpTCd524JS5CAwvJieLExqDvggI8ztFyGlITT-mQyPsNiApr2ah0CciUd432uAP3CcNpCEiFTWLfD4ls-BDXYocpKs/s1600/oneshot-latency.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi5P7ro_TtpIwobiivPBH0GXsED4hCyKm9pFc4q_ZdrGjJ3qh-qKNpTCd524JS5CAwvJieLExqDvggI8ztFyGlITT-mQyPsNiApr2ah0CciUd432uAP3CcNpCEiFTWLfD4ls-BDXYocpKs/s1600/oneshot-latency.png" height="239" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Anova results</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: left;">
<br />And the multiple comparison shows that both OneShot tests were significantly different than traditional mode.</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhUrGhMmM7t7Hk8CMyOT6Tb1jBugP88fhNcmqQukenVJ7AJ1Dc_IZJDYlg_Y7ARANyZoeUBn4_20erxhH6WGJZP93X8vwWtd0f3RTDx3lvU1_-1q3fGCec08yMuYxwbJNDg4lLGKz11J-E/s1600/oneshot-multcomp.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhUrGhMmM7t7Hk8CMyOT6Tb1jBugP88fhNcmqQukenVJ7AJ1Dc_IZJDYlg_Y7ARANyZoeUBn4_20erxhH6WGJZP93X8vwWtd0f3RTDx3lvU1_-1q3fGCec08yMuYxwbJNDg4lLGKz11J-E/s1600/oneshot-multcomp.png" height="239" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
<br />
<h2 style="text-align: left;">
Conclusion</h2>
</div>
<div>
Using OneShot mode on this quad results in about a 20% reduction in ESC latency. Even before OneShot, these KISS ESCs were pretty damn fast so it already flew really well. I'm not sure I'll be able to tell the difference in rate mode, but I do believe a better acro pilot than me could. I also didn't run these parameters through the system models to start seeing what the difference in effective control bandwidth will be for the outer loops (e.g. attitude).<br />
<br />
It also remains to be seen if there are similar benefits with BLHeli and I believe SimonK has support coming soon for OneShot. I'll probably repeat these tests once I have the right hardware.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com15tag:blogger.com,1999:blog-1759046512792102553.post-7418799419421960992015-01-24T17:01:00.004-08:002015-02-02T08:58:41.452-08:00EKF: Enhancements and Unit Tests<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
We have a very nice EKF that was written by Dale Schinstock from Kansas University that is used for navigation in our code. Generally it works quite well, although it is fairly sensitive to tuning parameters. I've discussed this somewhat in <a href="http://buildandcrash.blogspot.com/2014/03/magnetometer-handling-in-ins.html">this post about the magnetometer</a> and this about <a href="http://buildandcrash.blogspot.com/2014/03/vertical-control.html">vertical control</a>.<br />
<br />
One thing that I haven't liked (and has slown me down for rolling out updates to the EKF) is that we don't really have any test coverage of it - especially for various initial conditions and systematic biases that might exist.<br />
<br />
<h2 style="text-align: left;">
Unit tests</h2>
Recently I wrote a python wrapper that calls into the EKF. I've had something similar for Matlab in the past, but of course the problem with that is it requires a matlab license and cannot be easily integrated into a test environment. With this wrapper in hand, I wrote a series of uni tests (using the Python unittest platform). With this I can systematically test things like how rapidly it converges from various initial conditions given a set of inputs and measurements (with the option to visualize the results, but of course having this disabled when systematically testing things).<br />
<br />
For example, I can simulate bias gyro inputs and verify that it tracks that bias correctly<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiGwWnNOeqSOACKBS9dOSGYB2ZP6-gXlR3bwNgsSLKUPuceJgSiaOkBAReJ1InXJwkaWLB1xqaRPXe0iwXgE6YIR037kfptfplEMjoaflP38b1eJKCzWSPxKsyccupmJLSK4T72thscjRE/s1600/Screen+Shot+2014-11-28+at+11.46.13+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiGwWnNOeqSOACKBS9dOSGYB2ZP6-gXlR3bwNgsSLKUPuceJgSiaOkBAReJ1InXJwkaWLB1xqaRPXe0iwXgE6YIR037kfptfplEMjoaflP38b1eJKCzWSPxKsyccupmJLSK4T72thscjRE/s1600/Screen+Shot+2014-11-28+at+11.46.13+AM.png" height="211" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_gyro_bias</td></tr>
</tbody></table>
<br />
Or initialized at the totally wrong attitude, the EKF will converge to the correct one. Here, it takes longer than I would like and optimizing convergence times (through the EKF tuning) is on my list of things to do and then add worst case values to the test assertions.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEii2iT7baUmfM_ND6nnQJ_PcTL_ZwOolbX4-C3uVRIG9-Ywq7l392CHaMua57quhfNnZgIC_8KZvCWMTf8xCcDLBxCmvxXMoVnQZ5Ikkq8cG4Y8sPNFR_SdHAI6ky03pNI4Tc6ECni3W8c/s1600/Screen+Shot+2014-11-28+at+12.00.14+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEii2iT7baUmfM_ND6nnQJ_PcTL_ZwOolbX4-C3uVRIG9-Ywq7l392CHaMua57quhfNnZgIC_8KZvCWMTf8xCcDLBxCmvxXMoVnQZ5Ikkq8cG4Y8sPNFR_SdHAI6ky03pNI4Tc6ECni3W8c/s1600/Screen+Shot+2014-11-28+at+12.00.14+PM.png" height="203" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_init_bad_q_bias</td></tr>
</tbody></table>
<br />
When given a position different than the initial location, it quickly snaps to that location at the first update (because the initial position variance is quite high)<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjxyepboVdahhrx31AyNhDzZ4ikPrG3YhwTJ25CKmP3V7aOAmCTUxevt5bVIhiyOka6Pm8pe2o0TayhJ1C0afnylHLiqeas5EoTcgH1YHgbep6g0nLTtnk21n3y_tAuStSop1KT6Uc3HF0/s1600/Screen+Shot+2014-11-28+at+11.56.32+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjxyepboVdahhrx31AyNhDzZ4ikPrG3YhwTJ25CKmP3V7aOAmCTUxevt5bVIhiyOka6Pm8pe2o0TayhJ1C0afnylHLiqeas5EoTcgH1YHgbep6g0nLTtnk21n3y_tAuStSop1KT6Uc3HF0/s1600/Screen+Shot+2014-11-28+at+11.56.32+AM.png" height="210" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_pos_offset</td></tr>
</tbody></table>
It is also possible to inject noise and verify that the system remains stable in this case<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEirZb8QU9VllZHr_bQwzHfC6-q3vd_9ezd4fj1pw6w954oHpTJ3XFAQl7xdaerWsTh_ElfXs9Yvx5qk240HJQyLsxXnCt5Hvz5Zb3f_sG5uAd1_IMoI05j1-_aodIhuUSLQ17KQgoxKQfk/s1600/Screen+Shot+2014-11-28+at+1.26.57+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEirZb8QU9VllZHr_bQwzHfC6-q3vd_9ezd4fj1pw6w954oHpTJ3XFAQl7xdaerWsTh_ElfXs9Yvx5qk240HJQyLsxXnCt5Hvz5Zb3f_sG5uAd1_IMoI05j1-_aodIhuUSLQ17KQgoxKQfk/s1600/Screen+Shot+2014-11-28+at+1.26.57+PM.png" height="195" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_stable</td></tr>
</tbody></table>
<br />
<h3 style="text-align: left;">
Problematic cases</h3>
It can also expose certain problems with the current EKF. For example, if the mag isn't perfect (for example I shrink the z-axis measurement) that results in a biased attitude and the subsequently coupling bias into the velocity and position. In this case, the quad is meant to be sitting still at the origin (except for the mag). It also learns a bias (that isn't there) to explain why the attitude isn't making sense.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh-eZ1bfeDNaT7CoLKoFGqhLWQ-dk-9CVEtUPiqmvMfLpVd7QIJ-0ncD37LgoN8nNzF7XHifuofDJrkHd_PcmubDt5HoLTL10rpFVftVAxTPQnyfelo0WTkKWsOeV5ubK5OtSHujTQrl7w/s1600/Screen+Shot+2014-11-28+at+11.51.25+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh-eZ1bfeDNaT7CoLKoFGqhLWQ-dk-9CVEtUPiqmvMfLpVd7QIJ-0ncD37LgoN8nNzF7XHifuofDJrkHd_PcmubDt5HoLTL10rpFVftVAxTPQnyfelo0WTkKWsOeV5ubK5OtSHujTQrl7w/s1600/Screen+Shot+2014-11-28+at+11.51.25+AM.png" height="217" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_mag_offset</td></tr>
</tbody></table>
<br />
In a related problem, when simulating starting facing north and presenting mags consistent with facing East, it does reasonably but ends up picking up some roll/pitch errors that influence position:<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgx9VUo2acMivRMMTXMHDjvuqJj-AdseS0hS_E8WoPmDhdOqZbTj-iTjXzwN3bxbXoxrxGh6qRBSt3plvh2apAp95zgj6nKhodOk498PKTLZQxODkWDnn5qABh7ZZJ25FHDKSMJoPsYAGE/s1600/Screen+Shot+2014-11-28+at+11.54.41+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgx9VUo2acMivRMMTXMHDjvuqJj-AdseS0hS_E8WoPmDhdOqZbTj-iTjXzwN3bxbXoxrxGh6qRBSt3plvh2apAp95zgj6nKhodOk498PKTLZQxODkWDnn5qABh7ZZJ25FHDKSMJoPsYAGE/s1600/Screen+Shot+2014-11-28+at+11.54.41+AM.png" height="183" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_face_west</td></tr>
</tbody></table>
Another issue is that a fairly small (e.g. 0.2 m/s^2) bias in the accelerometers can really bias the vertical velocity and altitude<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhujWXQKsQhyKYjsCXpy6oKNzoEBw33hhYyn5-jOP271OlxCa9a8Mq7A2mPPWGM4jQ1c52-KDzC5jrG_oTwcv0w1w6zrZzX3rkTQ2qvAzCBkP0gWhKteiskVA28LexDlzOrGcO6la_ypkI/s1600/Screen+Shot+2014-11-28+at+12.08.39+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhujWXQKsQhyKYjsCXpy6oKNzoEBw33hhYyn5-jOP271OlxCa9a8Mq7A2mPPWGM4jQ1c52-KDzC5jrG_oTwcv0w1w6zrZzX3rkTQ2qvAzCBkP0gWhKteiskVA28LexDlzOrGcO6la_ypkI/s1600/Screen+Shot+2014-11-28+at+12.08.39+PM.png" height="193" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_accel_bias</td></tr>
</tbody></table>
<h2 style="text-align: left;">
Fourteen state EKF with mag-attitude decoupling</h2>
<div>
To address these shortcomings, I made two major changes to the EKF. The first, is to track the bias of <a href="http://buildandcrash.blogspot.com/2014/03/vertical-control.html">accelerometer in the z-axis direction</a>. The complementary filter used for altitude hold mode has such a feature and it proves quite useful for getting robust performance. We previously had a 16-state variant with biases on all three axes, but in my hands that is overkill and actually can be overparameterized - so there can be incorrect solutions to a given set of measurements that are not a good state.</div>
<div>
<br /></div>
<div>
The second was a bit trickier - to make the <a href="http://buildandcrash.blogspot.com/2014/03/magnetometer-handling-in-ins.html">magnetometer values only influence the heading</a> (in earth frame) without influencing roll and pitch. The solution to this is to pre-transform the measurement measurements by backing out the current estimate of roll and pitch. Then the predicted measurement is based only on the heading term. It ends up being quite a bit of math so I used matlab to rework all the equations and come up with an efficient covariance prediction matrix.</div>
<div>
<br /></div>
<div>
This combination ended up fixing those issues. For example, having a badly scaled (but facing the correct way) magnetometer reading ends up producing positively boring results, with no bias of the attitude:</div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiaFJyejH-JnqodRbMtv98YZVu-wfWl6gS50Zl_Y_UTBUdRND0AhP5ZXOQrcctKEDj0jzBKgAoxEGTAzuvHCc87du7KRR5RaU0q97no3mQyaan6DDgCj9q_bnAL9G5zbOc3IM-7azP0OyQ/s1600/Screen+Shot+2014-11-28+at+12.15.31+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiaFJyejH-JnqodRbMtv98YZVu-wfWl6gS50Zl_Y_UTBUdRND0AhP5ZXOQrcctKEDj0jzBKgAoxEGTAzuvHCc87du7KRR5RaU0q97no3mQyaan6DDgCj9q_bnAL9G5zbOc3IM-7azP0OyQ/s1600/Screen+Shot+2014-11-28+at+12.15.31+PM.png" height="198" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_mag_offset</td></tr>
</tbody></table>
<div>
<br /></div>
<div>
Starting facing the wrong way just nicely rotates around to the correct heading without any errors in the attitude (and thus no position errors)</div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgkuqXvUSn2amukgWFBUc0_vvIHyiVOtZIwY47n1e_1yYhYf9-YtAo-EFDSDJuTJqI_D7_Mbcmr_mTHwmEgQbXRc5dPeKgJh4ON66tFrlaUGCJ2Xlwi3W4pBGhqh83FRHKIWn8W1u6sAKE/s1600/Screen+Shot+2014-11-28+at+12.17.10+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgkuqXvUSn2amukgWFBUc0_vvIHyiVOtZIwY47n1e_1yYhYf9-YtAo-EFDSDJuTJqI_D7_Mbcmr_mTHwmEgQbXRc5dPeKgJh4ON66tFrlaUGCJ2Xlwi3W4pBGhqh83FRHKIWn8W1u6sAKE/s1600/Screen+Shot+2014-11-28+at+12.17.10+PM.png" height="187" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_face_west</td></tr>
</tbody></table>
<div>
<br /></div>
<div>
And having a biased accelerometer is nicely tracked and corrected for</div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhIKCV11Kmez8vm6v5JW-R1-O2bOtoKRpAW5otwPf1MdlesQ4HhIDyNsq-1XsEqcVr0UAEpSFmNZstUniohIcWW6e4YJHjMXlUiLUOzPxOf31bLsuN_kLz3AIt3znj6-jQZbCLNtsc7cCM/s1600/Screen+Shot+2014-11-28+at+12.20.13+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhIKCV11Kmez8vm6v5JW-R1-O2bOtoKRpAW5otwPf1MdlesQ4HhIDyNsq-1XsEqcVr0UAEpSFmNZstUniohIcWW6e4YJHjMXlUiLUOzPxOf31bLsuN_kLz3AIt3znj6-jQZbCLNtsc7cCM/s1600/Screen+Shot+2014-11-28+at+12.20.13+PM.png" height="212" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_accel_bias</td></tr>
</tbody></table>
<div>
<br /></div>
<div>
At the same time, it still correctly identifies when there is a bias in the gyros and learns this without having a problem identifying zero accel bias. Note that the position and velocity drift while it learns the gyro bias and gets the attitude correct</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjwjhoRrorAOpeZw1ofPmC7lFKKPr-CeIhBBUXY4LziOn_DS9oHYpuKiam2NpYsFjaLzC0g5fon8vd5r8C42uAELiD45d8egMgY3aoiL_Y6ijh9g_De2wy0WooKhDj73ARFU8HZ_CtbmtU/s1600/Screen+Shot+2014-11-28+at+12.21.59+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjwjhoRrorAOpeZw1ofPmC7lFKKPr-CeIhBBUXY4LziOn_DS9oHYpuKiam2NpYsFjaLzC0g5fon8vd5r8C42uAELiD45d8egMgY3aoiL_Y6ijh9g_De2wy0WooKhDj73ARFU8HZ_CtbmtU/s1600/Screen+Shot+2014-11-28+at+12.21.59+PM.png" height="226" width="320" /></a></div>
<div>
<br /></div>
<div>
[<i>Note to self. </i><span style="font-family: Courier New, Courier, monospace;">49549c3b9c682641d2461a90e176a2f3db7dc1b8</span> <i>passes all these tests</i>]</div>
<div>
<br /></div>
<h2 style="text-align: left;">
Tuning and optimizing convergence</h2>
<div>
Armed with a filter that can at least deal with some of the systematic errors we anticipate seeing on a multirotor (e.g. distorted mag fields, imperfect accel bias), the next step is to tune it to behave well in real life. There are a few sets of major parameters that define the EKF performance:</div>
<div>
<ul style="text-align: left;">
<li>gyro noise - Q[0..2], this is the amount of error expected between the gyro inputs and the change in state. increasing this variance will make the system trust the gyros less (and thus make things like the mags relatively more influential)</li>
<li>accel noise - Q[3..5], this is the amount of error expected between the accel inputs and the change in velocity. Increasing this variance will make the velocity estimation trust the GPS and baro relatively more. It will also alter how the roll and pitch are estimated - basically tuning between trusting the gyros versus accels)</li>
<li>bias walk - Q[6..9], how much the bias is expected to change during flight. Making this value smaller means the system will take longer to convergence when estimating the bias terms, but will be less likely to get random bias values when there is noise</li>
<li>gps position noise - R[0..2], how much noise is expected from the GPS position measurements. setting this lower will trust the GPS more and setting it higher will trust the integrated velocity estimate more</li>
<li>gps velocity noise - R[3..5], how much noise is expected from the GPS velocity measurements, setting this lower will trust the GPS more and setting it higher will trust the accel (and position) more</li>
<li>mag noise - R[6..8], how much noise is expected from the mag. trusting this more will get a more accurate heading but be more susceptible to anything that distorts the mags</li>
</ul>
<div>
There is also a component of redundancy amongst these term, in that the covariances can all be scaled by a constant without changing the behavior of the state estimate. However, it is convenient to try and preserve the real units (position in m, velocity in m/s, etc) so the variance has meaningful units (true m^2 variance).<br />
<br />
<h3 style="text-align: left;">
Bias convergence rates</h3>
<div>
One important parameter to converge quickly enough are the gyro bias terms. We try and initialize these at startup but still tracking changes in error is important and a critical function of the EKF. To test this I see how quickly the EKF learns the gyro bias (within 10%) after initialization. This takes multiple minutes to converge which is slower than we want in practice. Using this code we can increase the bias walk parameters for both the XY gyro, the Z gyro (which is affected differently since it gets corrections from mags instead of accels) and the Z accelerometer. The goal I wanted was for the gyros to converge within 10% of the correct value (when initialized at 10 deg/s off) within 30 seconds. For the accel bias I initialized with 1 m/s^2. After tweaking the variances this was achievable (without making it too fast -- thus tracking noise -- or failing any of the previous tests).</div>
<div>
<br /></div>
<div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh4oVOM5BrpXXG7_gRftB2YKWAktQab3ZcTQW6ye-VueaQIla_TSRnw2BquFWF23IiW43KMJv7djjyr4Ho8Y6ZuIZMl36z11ZySsrWohzaNPD4f1mBasaivu-hPLHGJ076Ffr-AtLMAOSI/s1600/Screen+Shot+2015-01-24+at+4.30.09+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh4oVOM5BrpXXG7_gRftB2YKWAktQab3ZcTQW6ye-VueaQIla_TSRnw2BquFWF23IiW43KMJv7djjyr4Ho8Y6ZuIZMl36z11ZySsrWohzaNPD4f1mBasaivu-hPLHGJ076Ffr-AtLMAOSI/s1600/Screen+Shot+2015-01-24+at+4.30.09+PM.png" height="229" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_gyro_bias</td></tr>
</tbody></table>
<br /></div>
Checking that it did fail any of the previous tests (including those with simulated noise) is critical because if the bias drifts around it can create very bad estimates.<br />
<br />
<h3 style="text-align: left;">
Changing biases</h3>
<div>
An initial mismatch in the biases is also different than a change during flight. The initial covariance parameters also play into the former. The later is important to be fairly stable although should still track slower changes. This can be simulated by letting the filter run for 30 seconds and then introduce the bias.</div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg4Rhj70adu1Hc9U4U_JP1DXY_2OSt6i8SvG1e3XAS97hvJ71K5TrQyEpvbydI5XijRCBNPm4b-OpdlCqZeHvvdigq60CVuV8S40gQDXbg5UdPuqMK7v-NmcgS724XBavbgDanIRSpI3ZA/s1600/Screen+Shot+2015-01-24+at+6.59.29+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg4Rhj70adu1Hc9U4U_JP1DXY_2OSt6i8SvG1e3XAS97hvJ71K5TrQyEpvbydI5XijRCBNPm4b-OpdlCqZeHvvdigq60CVuV8S40gQDXbg5UdPuqMK7v-NmcgS724XBavbgDanIRSpI3ZA/s1600/Screen+Shot+2015-01-24+at+6.59.29+PM.png" height="199" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">changing test_gyro_bias</td></tr>
</tbody></table>
<br />
You can see changing the gyro bias causes the accel bias to briefly change. This is because the biased attitude makes the velocity and position have error, but it self corrects. These influences are unavoidable in a coupled filter like the EKF. Similarly, we can change the accelerometer bias which takes a bit longer to correct.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEin-vM4x9kWksXziYK5_b2iWKIHRlRnUJ-LL7xDBlqYSyhPPUVsiYFLwo3LmafG0jO30CA9g3M-EubulnW9dNXppS6Vp4K3tvbyYqI4KnhoHgose5d8aCzwzi5R0l8_Pg5tNn0N8nGcKY4/s1600/Screen+Shot+2015-01-24+at+7.00.00+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEin-vM4x9kWksXziYK5_b2iWKIHRlRnUJ-LL7xDBlqYSyhPPUVsiYFLwo3LmafG0jO30CA9g3M-EubulnW9dNXppS6Vp4K3tvbyYqI4KnhoHgose5d8aCzwzi5R0l8_Pg5tNn0N8nGcKY4/s1600/Screen+Shot+2015-01-24+at+7.00.00+PM.png" height="247" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">changing test_accel_bias</td></tr>
</tbody></table>
<div>
<br /></div>
<h2 style="text-align: left;">
Replaying simulated flights</h2>
<div>
I also wrote a very simple simulator which mimics taking off and flying in circles (with a net drift) and passes that data plus noise to the real implementation of the EKF to make sure that it behaves correctly. Again, this can also be done with an initial bias added or incorrect state to verify that the system ends up at the correct state.</div>
<div>
<br /></div>
<div>
First for a simple flight without anything mismatched (except for sensor noise) the state estimates all do the correct things.</div>
<div>
<br /></div>
<div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgbhsIqODmdoSJ5XQwZTF73LYRpD5krB0scBQg5lSbIVmLtW88WsrT0X2eWwV6-H0_XLmbA4cMdj3VqLBAMLuY5PlZ_8wC85QVLsSqDOrZhdXuVTr04IjU5jl2lg2wkAxdEmsZyKb42qGA/s1600/Screen+Shot+2015-01-25+at+9.59.45+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgbhsIqODmdoSJ5XQwZTF73LYRpD5krB0scBQg5lSbIVmLtW88WsrT0X2eWwV6-H0_XLmbA4cMdj3VqLBAMLuY5PlZ_8wC85QVLsSqDOrZhdXuVTr04IjU5jl2lg2wkAxdEmsZyKb42qGA/s1600/Screen+Shot+2015-01-25+at+9.59.45+AM.png" height="215" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_circle</td></tr>
</tbody></table>
<br /></div>
<div>
Then we can test that it converges when initialized with the wrong attitude (the dotted line shows the real data):</div>
<div>
<br /></div>
<div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiOLAs3AeQTf9VcVL4l7k_eI4ykdqZFEp537bKEYQJI3168AFiOHt0a_awIFmpzgCx9myNiJGCNhXPICHyJkKwr0DjG1llCXHZf4vgDuD-buOTbfcjYkYbcYNCAQE4fR3qYLDPnsnLNsc4/s1600/Screen+Shot+2015-01-25+at+10.01.44+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiOLAs3AeQTf9VcVL4l7k_eI4ykdqZFEp537bKEYQJI3168AFiOHt0a_awIFmpzgCx9myNiJGCNhXPICHyJkKwr0DjG1llCXHZf4vgDuD-buOTbfcjYkYbcYNCAQE4fR3qYLDPnsnLNsc4/s1600/Screen+Shot+2015-01-25+at+10.01.44+AM.png" height="259" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_bad_init_q</td></tr>
</tbody></table>
<br /></div>
<div>
Or with either biased gyros or accels and check that it converges to the correct flight plan and bias values:</div>
<div>
<br /></div>
<div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhnUjLLkpCHfgekWh3VpTH0wJ8_A62tntI_GuqlVVI6AJYCCeshIdqjoHt3p4Bq834qB198qcT971xJGIKlOccSO3uSxETrOXgTAJwWp3QNtZ4P-kRSqAyDdc4p_zek2cSthRIykwOzylI/s1600/Screen+Shot+2015-01-25+at+10.03.33+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhnUjLLkpCHfgekWh3VpTH0wJ8_A62tntI_GuqlVVI6AJYCCeshIdqjoHt3p4Bq834qB198qcT971xJGIKlOccSO3uSxETrOXgTAJwWp3QNtZ4P-kRSqAyDdc4p_zek2cSthRIykwOzylI/s1600/Screen+Shot+2015-01-25+at+10.03.33+AM.png" height="275" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_gyro_bias_circle</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiDckOh9SQ_zAnkdaYrcUXQ2dide2aorGDHyePjwednWemRwlwBgEXEALlOfwr0kJZlncnx4iWlCHT5877Lkj2-N4Z7EJTfkhnYNcgffJWT7F6-DjviLRQcRzZPOxIY7eDJ4xJDh8iYYLA/s1600/Screen+Shot+2015-01-25+at+10.04.59+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiDckOh9SQ_zAnkdaYrcUXQ2dide2aorGDHyePjwednWemRwlwBgEXEALlOfwr0kJZlncnx4iWlCHT5877Lkj2-N4Z7EJTfkhnYNcgffJWT7F6-DjviLRQcRzZPOxIY7eDJ4xJDh8iYYLA/s1600/Screen+Shot+2015-01-25+at+10.04.59+AM.png" height="266" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">test_accel_bias_circle</td></tr>
</tbody></table>
This test is a really good one. Simulate the quad rocking pitch up and down while yawing. This is a good robust test on the mag attitude compensation. In fact I noticed at one point while doing this that I had an issue and the accel bias could wander a bit much. This led to me finding a bug in how the compensation was applied and fixing it. You can see below that the biases stay stable.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhFyFG58LtCp8INnJWC0hfgH8batz5-G9VE1uFDxe9J_bbADlSjrF7T6xnVVihk4nOSpsmeQpPrVrag6U7KJUQFGaAEQ2dAOAxhV3CxtruYvA7-yDFvR-DRXOe2wrE7IlHnNbtvyab0mQA/s1600/Screen+Shot+2015-01-26+at+5.21.56+PM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhFyFG58LtCp8INnJWC0hfgH8batz5-G9VE1uFDxe9J_bbADlSjrF7T6xnVVihk4nOSpsmeQpPrVrag6U7KJUQFGaAEQ2dAOAxhV3CxtruYvA7-yDFvR-DRXOe2wrE7IlHnNbtvyab0mQA/s1600/Screen+Shot+2015-01-26+at+5.21.56+PM.png" height="258" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">rock_and_turn</td></tr>
</tbody></table>
<br /></div>
<h2>
Replaying real flights</h2>
<div>
I've written about using python to analyze logs we collect <a href="http://buildandcrash.blogspot.com/2014/03/logging-and-python-parsing.html">here</a> and <a href="http://buildandcrash.blogspot.com/2014/12/more-log-analysis.html">here</a>, With this code it is also possible to replay log data a real flight. This is important because there are numerous places where the real world violations of the model might cause issues.<br />
<br />
Here is a replay of a position hold flight comparing to the real data (or online estimates). You can see the heading well tracked the previous estimate. The position tracked the real data. And finally, the biases were fairly stable through the flight, although perhaps with a bit more oscillation in the gyro bias than I would like.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjbPB1T-VKPl7ycKALdUADNi1i92b4S9qZNrUdsyfYH8MvnPhdhyLcv89ETe7XWIwF8zpeG5g0DRKCPOhY1hezOehJp-Wa2oh0zoNOoKVm7MFeN_XbBJeJkakJgS5yU1JE695VX7GAMKpw/s1600/Screen+Shot+2015-01-24+at+4.15.58+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjbPB1T-VKPl7ycKALdUADNi1i92b4S9qZNrUdsyfYH8MvnPhdhyLcv89ETe7XWIwF8zpeG5g0DRKCPOhY1hezOehJp-Wa2oh0zoNOoKVm7MFeN_XbBJeJkakJgS5yU1JE695VX7GAMKpw/s1600/Screen+Shot+2015-01-24+at+4.15.58+PM.png" height="213" width="320" /></a></div>
<br />
<br />
<h2 style="text-align: left;">
Flight tests</h2>
</div>
<div>
Of course all this simulation is all well and good, but what really matters is how well it performs. In practice the heading was nice and locked in and the annoying twitch in altitude that I had observed in the past when engaging position hold was gone.</div>
<div>
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/117686343" webkitallowfullscreen="" width="500"></iframe> </div>
<br /></div>
</div>
<div>
Here is another flight. This was flying <a href="http://buildandcrash.blogspot.com/2014/11/seeing-spark-sparky2-and-sparkybgc-quad.html">Seeing Spark</a> with <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky2</a> running this new INS and logging to the android app via a <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">TauLink</a>. I used the log files to generate a video overlay to better see the performance in time with the video. I was mostly flying in position hold mode and using the <a href="http://buildandcrash.blogspot.com/2014/01/loiter-mode-and-more-rth-testing.html">loiter</a> feature.<br />
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/118370663" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
The estimates for position look really good and track well with what the video shows the quad doing. Some of the time it drifted laterally but it pretty much always indicated that on the map, so this means it is most likely an issue of tuning rather than a problem with the filter. For vertical velocity it seemed to be generally in agreement with what the video showed. In forward flight, though, the altitude estimate did not seem to track as well - often indicating it was climbing while it was dropping. At the end of the maneuver the altitude estimate would drop rapidly to catch up. Interestingly, in a number of these occurrences it was my impression the climbrate plot was doing the correct thing (and contradicting the altitude estimate).<br />
<br />
This disagreement where the velocity looks correct and the altitude goes the opposite way suggests that the accels are producing fairly good data but the baro is not. It's possible the airframe shape of seeing spark with the board on the inside of a cavity creates negative pressure when flying forward. This could cause it to think it is climbing while it is not. I need to try repeating this with another open frame.<br />
<br />
<h4 style="text-align: left;">
Baro glitch</h4>
<div>
Here was another interesting moment. I was testing with Freedom on a QAV500 frame. I noticed in the logs some times when the baro put out REALLY weird values. Like shooting up 50m in a very short time. When analyzing the logs with video, something became really clear:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjYR8pIXI0EAVfXVxe2rJhRgHVJNtvPXsAC6xUL6JYYHmwfrBv9XGV0uKJtDzGeFsgNR_onWif6zmv7mB9qLvbHgsvDTntMCFR5xvMkSBLcyvv0Qw-p3iZMFt6v8XZs1r2eiKj_mxZ-5BU/s1600/Screen+Shot+2015-02-02+at+10.53.30+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjYR8pIXI0EAVfXVxe2rJhRgHVJNtvPXsAC6xUL6JYYHmwfrBv9XGV0uKJtDzGeFsgNR_onWif6zmv7mB9qLvbHgsvDTntMCFR5xvMkSBLcyvv0Qw-p3iZMFt6v8XZs1r2eiKj_mxZ-5BU/s1600/Screen+Shot+2015-02-02+at+10.53.30+AM.png" height="173" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
So the bottom right has this silly spiky pattern on altitude that is not real. Interestingly, they happen once every cycle while I'm spinning level. I realized, this is when the sun is hitting the baro. Definitely time to cover it.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com35tag:blogger.com,1999:blog-1759046512792102553.post-37611302539255280672014-12-31T14:35:00.000-08:002015-01-02T14:13:21.718-08:00More log analysis<div dir="ltr" style="text-align: left;" trbidi="on">
I've <a href="http://buildandcrash.blogspot.com/2014/03/logging-and-python-parsing.html">written previously</a> about using python and log parsing, which this writeup uses heavily.<br />
<br />
I was testing position hold with the new 14 state INS the other day with <a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky2</a> on <a href="http://buildandcrash.blogspot.com/2014/11/seeing-spark-sparky2-and-sparkybgc-quad.html">Seeing Spark</a>. The new filter is working great. I ran autotune and 6 point calibration and engaged position hold and it held beautifully still. The new estimation of the z-axis accel bias worked as it should so there was no glitch in the altitude. The new magnetometer handling meant that the attitude was wonderfully locked in and not biased while tracking the heading really well. Spinning around while holding and it didn't budge a bit.<br />
<br />
I wrote some code to calibrate the magnetometer while spinning which I think will be quite useful. It fits the data to a sphere as well as making sure the horizontal component has the appropriate magnitude (this prevents fitting to an edge condition).<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgLO0MpzVuu3QB1dajIyy_eBKyMxnlgNbqo9Nq9RIUYIomm18btgbCUDSMWwZMMigb3KPGNlI2GbQAFTL6t9FfgI4gO2xHilm2TVaF1iMXY6chi8cnO73Myw88bwXtJsUnc-qYB-3saUwE/s1600/Screen+Shot+2014-12-31+at+2.23.49+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgLO0MpzVuu3QB1dajIyy_eBKyMxnlgNbqo9Nq9RIUYIomm18btgbCUDSMWwZMMigb3KPGNlI2GbQAFTL6t9FfgI4gO2xHilm2TVaF1iMXY6chi8cnO73Myw88bwXtJsUnc-qYB-3saUwE/s1600/Screen+Shot+2014-12-31+at+2.23.49+PM.png" height="195" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<br />
You can see that the blue data (x versus y axis) quite nicely fits a circle. This is both an easier calibration procedure than 6 point and more useful since you can see the deviation from correct (the plot on the right shows the magnitude of the mag data) and the is performed with the motors running at hover. This will also work with the <a href="https://github.com/TauLabs/TauLabs/pull/1423">built in logging to flash</a>.<br />
<br />
<h3 style="text-align: left;">
Analyzing glitch</h3>
However, at one point it was just hovering and then started going to the side. I've occasionally seen things like this in the past and really wanted to get to the bottom of this. Whenever I started digging into navigation logs I typically end up writing the same lines in python over and over again. I finally decided to sit down and write a <a href="https://github.com/TauLabs/TauLabs/issues/1428">log analyzer</a> to facilitate this.<br />
<br />
<br />
<div class="p1" style="text-align: center;">
<span style="font-family: Courier New, Courier, monospace;">./python/logview.py -v TauLabs-2014-12-31_16-11-30.tll</span></div>
<div class="p1">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiMnZamLMDEIboD12SkL4ToEc67D5ReqIeViwYUiMscchepnQcWe21Fn-Ru7V9cDV69SB7zeaW4DukMuPih4-Byoaxhqnbu4X871JHDfKM8dEgNqy1WH-TlxTIHkNehMWVZPeBHBqIQ6fY/s1600/Screen+Shot+2014-12-31+at+2.38.39+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiMnZamLMDEIboD12SkL4ToEc67D5ReqIeViwYUiMscchepnQcWe21Fn-Ru7V9cDV69SB7zeaW4DukMuPih4-Byoaxhqnbu4X871JHDfKM8dEgNqy1WH-TlxTIHkNehMWVZPeBHBqIQ6fY/s1600/Screen+Shot+2014-12-31+at+2.38.39+PM.png" height="197" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="p1">
<br /></div>
<div class="p1">
This shows a snippet of the log file. The upper left panel shows the position and the upper right the velocity. You can see there is substantially less than a meter movement while holding and very low velocities. The bottom left shows the attitude and there are only a few degrees perturbation. The bottom right shows the gyro and shows that the quad was spinning around at the time. The interface also has a few options to toggle extra plots.</div>
<div class="p1">
<br /></div>
<div class="p1">
I zoomed in on when the hold deviation occurred:</div>
<div class="p1">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiqQ4usMzMRN_tYFs082-RbRGI7bK8sVRI3vtrOM22hnsQV2mn1bUewoayFf5bkphCMkqFg_kbKFmx4GkNq8TO6MVnndeiUJ6n5rpT9eynu1uNsMPAlns8S0FawQRlN56JuythKAuq-GDI/s1600/Screen+Shot+2014-12-31+at+2.51.17+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiqQ4usMzMRN_tYFs082-RbRGI7bK8sVRI3vtrOM22hnsQV2mn1bUewoayFf5bkphCMkqFg_kbKFmx4GkNq8TO6MVnndeiUJ6n5rpT9eynu1uNsMPAlns8S0FawQRlN56JuythKAuq-GDI/s1600/Screen+Shot+2014-12-31+at+2.51.17+PM.png" height="202" width="400" /></a></div>
<div class="p1">
<br /></div>
<div class="p1">
What was extremely informative about this is that you can see the raw GPS position and velocity jump by a few meters at 188 seconds. Critically this occurs <i>before</i> the attitude deviates and not as a result of flying. Here is that time point zoomed in:</div>
<div class="p1">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwJe0EhNa7NTNmGztJJLvPJjliFKTnEvkTbn79sGCwKj8hnLCkfBslky6Bny2nnV59F5DIBtv9YrOXlMdNQB7t6WShMAxMKsqkozYf9wK19kY-TFQqyRFptF2MywxjKvK52QlQtT5m3sI/s1600/Screen+Shot+2014-12-31+at+2.58.11+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwJe0EhNa7NTNmGztJJLvPJjliFKTnEvkTbn79sGCwKj8hnLCkfBslky6Bny2nnV59F5DIBtv9YrOXlMdNQB7t6WShMAxMKsqkozYf9wK19kY-TFQqyRFptF2MywxjKvK52QlQtT5m3sI/s1600/Screen+Shot+2014-12-31+at+2.58.11+PM.png" height="320" width="217" /></a></div>
<div class="p1">
<br /></div>
<div class="p1">
Again showing that there are clearly sample with the attitude nearly horizontal right up to the point where the bad position sample comes. In addition, you can see the INS racing to catch up (which wouldn't happen if there was a real change first since the accelerometers would sense it).</div>
<div class="p1">
<br /></div>
<div class="p1">
The end result of this bad position sample was the UAV flies the opposite direction to fix the perceived error. This is a tough problem since we have to trust the GPS generally to have any hope of a good position hold. It is also exactly what ArduCopter had to implement GPS glitch protection to solve. It has been extremely rare in my experience and within 2 seconds the GPS had corrected the error. However, it is definitely something where I'd like to get better logs.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com9tag:blogger.com,1999:blog-1759046512792102553.post-69234807170571526032014-12-20T15:55:00.001-08:002014-12-20T15:55:31.889-08:00BrainFPV - cool new board using Tau Labs<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
I was lucky enough to get a <a href="http://www.brainfpv.com/">BrainFPV</a> from HeliShredder last week, which is a new flight controller that uses Tau Labs.<br />
<br />
<div style="text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjWOsWxUhZ3CRLAeEfLj4djArItMOCxtt_whD4MhxdqR37YiZfdHZzfcmzf2-ggpgY9LYgUteU1CWmVn13MHx76dX_tifbxVxlaX1J_8qlCLP5AgbxhLXJRVbzd4ekN_asuRbbeVKGofQQ/s1600/IMG_20141211_162031.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjWOsWxUhZ3CRLAeEfLj4djArItMOCxtt_whD4MhxdqR37YiZfdHZzfcmzf2-ggpgY9LYgUteU1CWmVn13MHx76dX_tifbxVxlaX1J_8qlCLP5AgbxhLXJRVbzd4ekN_asuRbbeVKGofQQ/s1600/IMG_20141211_162031.jpg" height="320" width="306" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<span id="goog_490949146"></span><span id="goog_490949147"></span><br /></div>
<div style="text-align: center;">
<br /></div>
<br />
It is an impressive board with a lot of features in it's 36x36 mm size. Beyond having a full sensor suite (3-axis gyro, 3-axis accel, mag, and baro), its biggest unique feature is of course an integrated OSD.</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="250" src="//www.youtube.com/embed/Tmo8axMxA4s" width="425"></iframe></div>
<br />
This kind of integration also gives a lot of power - like the ability to switch OSD display modes on the fly.<br />
<br />
I'll just paste from Brain's page for htFPV Specific Features:<br />
<br />
<b>FPV features:</b><br />
<br />
<ul style="text-align: left;">
<li>Full-graphic OSD (360x266 for PAL):</li>
<ul>
<li>Software adjustable black and white levels</li>
<li>PAL/NTSC autodetect</li>
<li>4 fully user configurable OSD pages, selectable using switch on transmitter</li>
</ul>
<li>Audio output (not yet supported by software)</li>
<li>3 analog inputs for voltage, current, RSSI measurement</li>
<li>RSSI measurement using PWM, PPM, or analog input</li>
<li>Other Features:</li>
</ul>
<br />
<b>Other features:</b><br />
<br />
<ul style="text-align: left;">
<li>CPU: STM32F405RG (32bit, 168MHz, 192kB RAM, 1MB Flash)</li>
<li>64Mbit flash for settings, way points, logging</li>
<li>InvenSense MPU-9250 latest generation 3-axis gyro/accel/mag</li>
<li>Barometer: MeasSpec MS5611</li>
<li>Receiver compatibility: PWM, PPM, S.Bus, DSM2, DSMX, HoTT SUMD/SUMH</li>
<li>Up to 10 PWM outputs (up to 400Hz update rate) </li>
<li>Up to 3 serial ports for telemetry, GPS, RC receiver, etc.</li>
<li>External I2C port, can e.g. be used with an external HMC5883 compass</li>
<li>Micro USB port for configuration via PC </li>
</ul>
<h2 style="text-align: left;">
Installing into MHQ Quadcopter</h2>
<div>
To test it out, I decided to use my <a href="http://buildandcrash.blogspot.com/2014/02/microquad-from-hovership-pro.html">foldable MHQ quadcopter</a> from Steve (<a href="http://www.thingiverse.com/thing:251002">thingiverse link</a>). First I had to splice a JST connector into the video line so it could plug into the BrainFPV controller.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiJvX4vVXl-nr_0zUbFYW5Lu6z4B2iBELhl5hMt6ZFT_3LyDG4xdfrg_YvOfedGusn7Dx3A_B6zl7Ag7N-j7zuC61HihX13jaAY8r2oJu_wIUkR_UcrNphLFswCszZgSRdmKmQ7tmetIXc/s1600/IMG_20141220_162312.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiJvX4vVXl-nr_0zUbFYW5Lu6z4B2iBELhl5hMt6ZFT_3LyDG4xdfrg_YvOfedGusn7Dx3A_B6zl7Ag7N-j7zuC61HihX13jaAY8r2oJu_wIUkR_UcrNphLFswCszZgSRdmKmQ7tmetIXc/s1600/IMG_20141220_162312.jpg" height="310" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
This is the <a href="http://www.getfpv.com/lumenier-cp-520-pico-520tvl-nano-camera.html">Pico camera from GetFPV</a> with a <a href="http://www.thingiverse.com/thing:341752">mount that I designed</a> to hold it in the MHQ. Then I plugged it into the BrainFPV and immediately had a nice little OSD showing.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiBZX4i2Mf6GrC8AtktZtuCGzMHHTGwmRszR0ijlE_aqYhs_IsdbtHCB9h4W4yrruX0e12K2p8yDXUvm1qaKu3gnnovB4M-e8yA__cfZIaqGFfkoJ40Ha3itnMlZlpTxUiAzWbeLiemD-A/s1600/IMG_20141220_162945.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiBZX4i2Mf6GrC8AtktZtuCGzMHHTGwmRszR0ijlE_aqYhs_IsdbtHCB9h4W4yrruX0e12K2p8yDXUvm1qaKu3gnnovB4M-e8yA__cfZIaqGFfkoJ40Ha3itnMlZlpTxUiAzWbeLiemD-A/s1600/IMG_20141220_162945.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg1Z2W2LrLsWbyExHJXFE9tLSi-tZbpYr8THIxnurHQYzD8qCgsgRizcajQAhbnIKo2mCkw15-nSS7GmqTzSxRUr3Eeh2JsLyhbY1dZ3hFYGBOQCili60P64dcC9O0j4_celex0n-1i4rk/s1600/Screen+Shot+2014-12-20+at+5.22.07+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg1Z2W2LrLsWbyExHJXFE9tLSi-tZbpYr8THIxnurHQYzD8qCgsgRizcajQAhbnIKo2mCkw15-nSS7GmqTzSxRUr3Eeh2JsLyhbY1dZ3hFYGBOQCili60P64dcC9O0j4_celex0n-1i4rk/s1600/Screen+Shot+2014-12-20+at+5.22.07+PM.png" height="239" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Unfortunately my video recorder crops the edges so you can't see most of the OSD field. In the GCS you can also modify the layout, white black balance, and even switch the layout with a toggle of the switch.</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgc4ygUgii1C7zq1Mk4i8kYuxSAYiOVUtHLQpB76lHSmvAD_iu03IidYnaC1-4JGhGfxv3rEwm5mH63Sm6P1wokmNx4IoJLPbmMWd4wKts78Ib491K6xAHM4LEOc8KsUcS0lu5j8jeRMLU/s1600/Screen+Shot+2014-12-20+at+4.53.24+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgc4ygUgii1C7zq1Mk4i8kYuxSAYiOVUtHLQpB76lHSmvAD_iu03IidYnaC1-4JGhGfxv3rEwm5mH63Sm6P1wokmNx4IoJLPbmMWd4wKts78Ib491K6xAHM4LEOc8KsUcS0lu5j8jeRMLU/s1600/Screen+Shot+2014-12-20+at+4.53.24+PM.png" height="229" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div>
HeliShredder did a nice job of fitting the OSD configuration into the configuration gadget. With it all tested, then I just had to finish reassembling my quadcopter.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhwjoy3mUZ1z3fAJ0aMWyYbLOd_47Y9wjuwWfgUNAXbVfAGIddcVAI6ZBBqyrbsFXGrbSX2juO_U3G45oNEzh2jZphHUFSRhwmZNLYHo9qxSy9DiKzz9CIY0Qf_4rnNqgcvyn3hQTiUfcQ/s1600/IMG_20141220_163725.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhwjoy3mUZ1z3fAJ0aMWyYbLOd_47Y9wjuwWfgUNAXbVfAGIddcVAI6ZBBqyrbsFXGrbSX2juO_U3G45oNEzh2jZphHUFSRhwmZNLYHo9qxSy9DiKzz9CIY0Qf_4rnNqgcvyn3hQTiUfcQ/s1600/IMG_20141220_163725.jpg" height="240" width="320" /></a></div>
<br />
It definitely makes the wiring really nice and simple having just that one board. I really need to get add a battery current/voltage sensor to this frame now, since the OSD can show that to me. I just hate soldering on the wiring harness :(<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgoOnakDNAbd3xEfR5px_DUHoB4Xs6Wyyw3ClU3msYchI5zlcdbmqBpt7icNp4S7lVumbzUFVD2CH3lHQehFT9zT3J5RaNQ67ZCoYo1T8b3ANs7U5m6ppjnSIGq4yctjHBiXJ9A-9td9MU/s1600/IMG_20141220_171045.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgoOnakDNAbd3xEfR5px_DUHoB4Xs6Wyyw3ClU3msYchI5zlcdbmqBpt7icNp4S7lVumbzUFVD2CH3lHQehFT9zT3J5RaNQ67ZCoYo1T8b3ANs7U5m6ppjnSIGq4yctjHBiXJ9A-9td9MU/s1600/IMG_20141220_171045.jpg" height="240" width="320" /></a></div>
<div>
<br /></div>
<div>
And all closed up and ready to fly. Time to practice my FPV flying ... indoors ...</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjFn28JpMbzZ4BB5UMKRw2bKRnwVRQJ7IksRb3gELWTdeU49f0v2cCNbV8zsENaPc2flcE_0_4tAkwL_ocIxjSZj7ic28DTy3AIPVjJ-trBh5dKSJa4IXyyRM-vmscFhcqQ6SMBXEKysUk/s1600/Screen+Shot+2014-12-20+at+5.28.45+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjFn28JpMbzZ4BB5UMKRw2bKRnwVRQJ7IksRb3gELWTdeU49f0v2cCNbV8zsENaPc2flcE_0_4tAkwL_ocIxjSZj7ic28DTy3AIPVjJ-trBh5dKSJa4IXyyRM-vmscFhcqQ6SMBXEKysUk/s1600/Screen+Shot+2014-12-20+at+5.28.45+PM.png" height="240" width="320" /></a></div>
<div>
<br /></div>
<div>
You can see a bit of line noise from the motors. It is recommended to have a filter on the power line, but I don't have one at the moment. I'd recommend checking out HeliShredder's videos to better see the performance.</div>
<div>
<br /></div>
<h2 style="text-align: left;">
OSD History</h2>
<div>
I'm really stoked to see this board out there and running Tau Labs. Hopefully the hardware designs will be open sourced in the not-too-distant-future and it can become included as an official target.</div>
<div>
<br /></div>
<div>
Sambas (now with the LinuxDrone project) started the OSD project in <a href="https://www.google.com/url?sa=t&rct=j&q=&esrc=s&source=web&cd=1&cad=rja&uact=8&ved=0CCAQFjAA&url=http%3A%2F%2Fforums.openpilot.org%2Ftopic%2F6736-openpilot-osd-prototyping%2F&ei=0AeWVKW5CceZgwSf44JA&usg=AFQjCNEiCLpEXkZSkwxwDoJaI8xCY9u4Vw&sig2=02f0kNkaY9eVwz2Cmxg72g&bvm=bv.82001339,d.eXY">2011</a> back with OpenPilot. The original design had some issues and I ended up cutting up one of the prototypes to design a new way of syncing the two SPI channels together. </div>
<div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGj7PZzTbazi7DD6yvSQsU9i4Pp2tosNDtID4v4wDACaB9MZ0Wv5mq7emQ778uXKMi6COjIR2V6pAVZxxZBfPDs1wj_w1nH8OK0-quDNjGZhFFISlvGDWFZAjJ2AZgPi9U7dFNDcmHsSw/s1600/IMG_20141025_181911.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGj7PZzTbazi7DD6yvSQsU9i4Pp2tosNDtID4v4wDACaB9MZ0Wv5mq7emQ778uXKMi6COjIR2V6pAVZxxZBfPDs1wj_w1nH8OK0-quDNjGZhFFISlvGDWFZAjJ2AZgPi9U7dFNDcmHsSw/s1600/IMG_20141025_181911.jpg" height="286" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
The end result was we got it going, although with some issues that limited drawing to the edge of the screen and required running the microcontroller at a strange rate.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
</div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="200" src="//www.youtube.com/embed/LZB7UmF8k8E" width="320"></iframe>
</div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: left;">
I believe some more work was done on the code subsequently, but ultimately the OSD with OpenPilot stagnated and nothing came of it. Luckily HeliShredder came along at picked up the code and ran with it. I believe he'd previously also had some experience developing on the Super-OSD project in the past.</div>
<div style="text-align: left;">
<br /></div>
<div style="text-align: left;">
Interestingly, he independently came up with a better way to sync the SPI channels that resolved those issues that Sambas and I had discussed way back when and it works great. There is also some nice tricks he used to also adjust the white / black balance to make sure it always looks nice that ended up an issue for us. He also did a lot of work to optimize the code so it can run with the flight controller jitter-free as well as the configuration interface to make it adjustable. </div>
<div style="text-align: left;">
<br /></div>
<div style="text-align: left;">
Ultimately, this is a great example of open source where something would have otherwise died in a pile of unused code (sadly <a href="http://buildandcrash.blogspot.com/2011/11/esc-development.html">like my ESC </a>has become) is now improved and used and I think will make a lot of people happy. Consistent with OSS principles, all his changes are available on <a href="https://github.com/BrainFPV/TauLabs">github</a>.</div>
<div style="text-align: left;">
<br /></div>
<h2 style="text-align: left;">
Final Thoughts</h2>
</div>
<div>
This board is going to be really popular, I suspect. Of course since it runs Tau Labs (and from my limited testing) it flies wonderful ;-) and I was able to simply import my configuration on this frame from when it was running Sparky and immediately it was tuned and flew well.</div>
<div>
<br /></div>
<div>
The OSD looks super crisp and sharp with good black and white levels and responds nice and quickly. I haven't even tried the modes where it shows waypoints and such, but apparently it does that. I can't wait to throw the battery monitor and GPS on there so I can see my speed, direction to home and battery status.</div>
<div>
<br /></div>
<div>
Between this and Gemini, I really need to spend more time FPVing.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com12tag:blogger.com,1999:blog-1759046512792102553.post-39199445489474412612014-11-02T13:28:00.000-08:002015-05-13T13:13:41.723-07:00Seeing Spark - Sparky2 and SparkyBGC quad<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div class="separator" style="clear: both; text-align: center;">
<b style="background-color: white; color: #222222; font-family: Arial, Tahoma, Helvetica, FreeSans, sans-serif; font-size: 13.1999998092651px; line-height: 18.4799995422363px; text-align: left;">Update: Sparky2 is available here <a href="http://www.hobbiesfly.com/taulabs-sparky2-0.html" style="color: #888888; text-decoration: none;">http://www.hobbiesfly.com/taulabs-sparky2-0.html</a></b></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
One of my longer term goals for a while is a system that can chase me around and film my friends and myself having fun. This seems to be a trendy topic this year with piles of kickstarter projects about this, so I won't pretend this is a unique idea. However I finally have something that is getting close. You can find this on <a href="http://www.thingiverse.com/thing:532808">Thingiverse</a>.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjErQ0Vy3kDI76BMnBFN0KbtpAY67NuZoRwJXseHVpdipeHLbMNcjNIz7uDS5VOn40O2yC1jYwNj5aWG1VtnvZl7PhO7WaxQtduSyqDVC5cliubmwVEbx0gZZJFhGnYpCwfcNZ1GfpESbM/s1600/IMG_20141103_112228.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="272" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjErQ0Vy3kDI76BMnBFN0KbtpAY67NuZoRwJXseHVpdipeHLbMNcjNIz7uDS5VOn40O2yC1jYwNj5aWG1VtnvZl7PhO7WaxQtduSyqDVC5cliubmwVEbx0gZZJFhGnYpCwfcNZ1GfpESbM/s1600/IMG_20141103_112228.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/110723868" webkitallowfullscreen="" width="500"></iframe>
</div>
<h3 style="text-align: left;">
Boards</h3>
Some of my recent boards have been coming together towards this aim (see <a href="http://buildandcrash.blogspot.com/2014/10/reflecting-on-four-years-of-development.html">this post</a> for a longer discussion of boards and some history). Sparky BGC is a cleaned up revision on my <a href="http://buildandcrash.blogspot.com/2013/05/sparky-brushless-gimbal-controller.html">previous daughter board for Sparky</a> (providing BGC outputs to a normal Sparky) and adding an external sensor board for light weight gimbals. It also drops the whole thing into the standard 36x36 mm board size which makes it very convenient to stack up with a Sparky.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhqGC2IrRU7chSYphcL_c0IV2nBSR0dMna_5FxRYW-kC3PBB2UIXNCH3Vjq0Z645AjNwRGKTC_rbLL_cAyRE32Ez-7_hIjv1pN_uVGI3EzzUWHgK8xoNewgTodfij2RN_tNjPsbePmJ2i8/s1600/IMG_20141025_161056.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="290" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhqGC2IrRU7chSYphcL_c0IV2nBSR0dMna_5FxRYW-kC3PBB2UIXNCH3Vjq0Z645AjNwRGKTC_rbLL_cAyRE32Ez-7_hIjv1pN_uVGI3EzzUWHgK8xoNewgTodfij2RN_tNjPsbePmJ2i8/s1600/IMG_20141025_161056.jpg" width="320" /></a></div>
<br />
<a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Tau Link</a> is a miniature radio board that works with the <a href="https://play.google.com/store/apps/details?id=org.taulabs.androidgcs">Tau Labs Android GCS</a> for telemetry. I ended up doing another revision that shrinks it down and adds a male USB connector which is more convenient when quickly plugging into an OTG cable or laptop.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_mwxeSdoZDaLY7ElxQezUgKv_KB8XDjkhLk0fUueBqjZ2bdBcsMQWKwDf4cO86f7NrwqjEUljqksQ2fYLYSMfn9DcB2-_CrBgPpvmi-ldByYw7A5c6X5zrMkjLmos3aGw5EDYKTwOV0s/s1600/IMG_20141025_161016.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="320" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_mwxeSdoZDaLY7ElxQezUgKv_KB8XDjkhLk0fUueBqjZ2bdBcsMQWKwDf4cO86f7NrwqjEUljqksQ2fYLYSMfn9DcB2-_CrBgPpvmi-ldByYw7A5c6X5zrMkjLmos3aGw5EDYKTwOV0s/s1600/IMG_20141025_161016.jpg" width="315" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky 2</a> is a pretty major overhaul of <a href="http://buildandcrash.blogspot.com/2013/05/sparky-testing-and-building-no-crashing.html">Sparky 1,</a> adding lots more IO and processing power, as well as radio capabilities which is convenient for communicating with Tau Link and ground stations.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEha2l5adRzIqHcoR8EmmZuMAk1w0vZCyhQpuMWEWbMlfsBQYnEoQVN2az53r8RieDrwY_D57WcQUTcO9P3-prRP_1LRamii0rn0eITkSr4MbVxR68rSHERaXfkTmYeoquFjfPlZyGmhniY/s1600/IMG_20141025_160908.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="310" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEha2l5adRzIqHcoR8EmmZuMAk1w0vZCyhQpuMWEWbMlfsBQYnEoQVN2az53r8RieDrwY_D57WcQUTcO9P3-prRP_1LRamii0rn0eITkSr4MbVxR68rSHERaXfkTmYeoquFjfPlZyGmhniY/s1600/IMG_20141025_160908.jpg" width="320" /></a></div>
<br />
One of the nice things about Sparky2 and SparkyBGC is that they both support CAN which provides a robust high-speed bidirectional communication bus between both boards. This means that Sparky2 (or Sparky1) can tell the gimbal about the desired angle to a position of interest for the camera.<br />
<br />
<i>Through discussion on IRC recently, I also realized that means it is possible to pass the heading measurements from the magnetometer on the gimbal (which is often fairly far from the motors) back to the flight controller to provide an external magnetometer for free. I'm pretty excited to try this.</i><br />
<br />
All this means that the android application can easily pass the tablet or phone location up to the UAV, which can then point the camera at that location and acquire nice stabilized video. I have a few multirotors with gimbals that could be used for testing this, but they are all big and less conveinent for testing, so it was design time!<br />
<br />
<h3 style="text-align: left;">
Power distro</h3>
I also really wanted to try out KISS ESC18A, which are tiny little things and also do not provide a BEC outputs. That seemed like a great motivator to make a power distro board that would route the PWM signals to these little ESCs and provide 5V to the flight controller. This board also provides current and voltage monitoring back to Sparky2 and comes in at just a hair below 30mm square.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhOxAFJyaWxhmS5oP1cgog4GdLmuBK1oOoBNlZWxdnF0JfzCzp-kz2KO6OJ9zFdGGi0iq1YAGObvV6IgJaU37_g1SL67AClWYcWk0YDOgGyfEgUBsZo6IGUzZEGRrDcApkMHrl9eXDqVu4/s1600/pdb+unpopulated.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="320" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhOxAFJyaWxhmS5oP1cgog4GdLmuBK1oOoBNlZWxdnF0JfzCzp-kz2KO6OJ9zFdGGi0iq1YAGObvV6IgJaU37_g1SL67AClWYcWk0YDOgGyfEgUBsZo6IGUzZEGRrDcApkMHrl9eXDqVu4/s1600/pdb+unpopulated.jpg" width="307" /></a></div>
<br />
You can see the wires for current voltage monitoring coming off the top, and for the ESC outputs below. The extra two outputs at the bottom at 5V and 0V. The footprints align to the KISS ESCs but can also be connected to any other ESCs. The connections for the PWM line are routed quite carefully around the edge to not obscure the power planes.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjMVqdfJ-Il_GV7NRD5p2_q4ngNalMwAg_gzdrq0NM0iEZsVmvu7o8SkFj4bihXfgCGkOM9RC5Y96wOrWh88Ten1OOiaOm-czxIhX3amMPs3zucssCH4IBB5XEcFdQFfaFoEVK10uT_mgg/s1600/pdb_zoom.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="194" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjMVqdfJ-Il_GV7NRD5p2_q4ngNalMwAg_gzdrq0NM0iEZsVmvu7o8SkFj4bihXfgCGkOM9RC5Y96wOrWh88Ten1OOiaOm-czxIhX3amMPs3zucssCH4IBB5XEcFdQFfaFoEVK10uT_mgg/s1600/pdb_zoom.jpg" width="320" /></a></div>
<h3 style="text-align: left;">
</h3>
<h3 style="text-align: left;">
Frame Design</h3>
<div>
The goal was something about as small as I could achieve that could carry a mobius camera and stabilize it with the above hardware. I started with something similar in my mind as <a href="http://buildandcrash.blogspot.com/2014/07/flying-spark-3d-printed-mini-quad.html">Flying Spark</a>. I wanted a closed canopy over most of the hardware with the battery on the inside. I also wanted the gimbal integrated into the main body to keep it compact.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEihLlz_lPZN71FHlxWPAQgNw1iG6vylxNX0KddrqeH3pdIfRrkW7YbFR0RYjeX7vnhjMCih3RBiH03VgpIKBErLagYJ0ifJwYo3R1_m0upLUvQLxyH_tyPVB89cIKkJ_Pl9HodLia65RHI/s1600/Screen+Shot+2014-10-27+at+11.11.53+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="196" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEihLlz_lPZN71FHlxWPAQgNw1iG6vylxNX0KddrqeH3pdIfRrkW7YbFR0RYjeX7vnhjMCih3RBiH03VgpIKBErLagYJ0ifJwYo3R1_m0upLUvQLxyH_tyPVB89cIKkJ_Pl9HodLia65RHI/s1600/Screen+Shot+2014-10-27+at+11.11.53+PM.png" width="320" /></a></div>
<div>
<br /></div>
<div>
It wasn't possible to design a solid body that could hold all the components that could be assembled as a single piece. One thing I ended up doing to get it quite compact was to make a recessed pocket in the main body for the ESCs and PDB and hand the flight controller and gimbal controller from the top of the canopy, and then printing it upside down.</div>
<div>
<br /></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgsuiSEA8uKln4UhU69S3ppyBiWNjdBUUFYSOC2pyRfUN00sWPB-uxzBkHsDtTgZt9dSNnVegCuSItAfslg4AoeDBDdgpWurXtfu5-dXFSwDTvV26U5F_tkbKBQpFkIEolGqiK76jW7bzo/s1600/Screen+Shot+2014-10-14+at+9.08.12+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="247" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgsuiSEA8uKln4UhU69S3ppyBiWNjdBUUFYSOC2pyRfUN00sWPB-uxzBkHsDtTgZt9dSNnVegCuSItAfslg4AoeDBDdgpWurXtfu5-dXFSwDTvV26U5F_tkbKBQpFkIEolGqiK76jW7bzo/s1600/Screen+Shot+2014-10-14+at+9.08.12+AM.png" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
The arms have a little protective hub around the motors and a channel for the wires to run into the body.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjRGp1e98CxKfY9JG5gA_Ww2-egFN25t5Gtpifn7qoNTW5zUEou216io-nyxTj6OlaiRWv3yAbD9dgHc3Au67tZzm5Eduqo9HVyRZObyaaAhOmnFq4Yg6l5OR3KuQdXciVZ59mCONoFe1Q/s1600/arm.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="170" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjRGp1e98CxKfY9JG5gA_Ww2-egFN25t5Gtpifn7qoNTW5zUEou216io-nyxTj6OlaiRWv3yAbD9dgHc3Au67tZzm5Eduqo9HVyRZObyaaAhOmnFq4Yg6l5OR3KuQdXciVZ59mCONoFe1Q/s1600/arm.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
The cables then go into the central body to the ESCs.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi67jbiTF9hc5Cs7w_IXrVOMhggndxN9vK5cR4aAaqmuiDi1_-1kBrUFcHEpgBClVuXEIgQjhwFqlfOsDG686HZiak0WcAnMFsgTLMOo4A4MwMhNZdD6IDiYUG4R0PkM9HMyjcuLdQhJyM/s1600/escs.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi67jbiTF9hc5Cs7w_IXrVOMhggndxN9vK5cR4aAaqmuiDi1_-1kBrUFcHEpgBClVuXEIgQjhwFqlfOsDG686HZiak0WcAnMFsgTLMOo4A4MwMhNZdD6IDiYUG4R0PkM9HMyjcuLdQhJyM/s1600/escs.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Here are the ESCs and power distribution board installed into the body of the frame.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhyP3BmRv_k0VazWc0h_htsPEr1RPY2TN1A3Rc1lY4eocEm51gGOzMVqWc8KbSagea2yqgvRIV1zAGm4Klzog1ubo1Hd2nBT4YyCDS1ElTOdjdfKOiiwQ1C6Gq8UnFF-im59z04drF7OcY/s1600/esc+solder.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhyP3BmRv_k0VazWc0h_htsPEr1RPY2TN1A3Rc1lY4eocEm51gGOzMVqWc8KbSagea2yqgvRIV1zAGm4Klzog1ubo1Hd2nBT4YyCDS1ElTOdjdfKOiiwQ1C6Gq8UnFF-im59z04drF7OcY/s1600/esc+solder.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And then Sparky2 and SparkyBGC installed into the bottom of the canopy and connected to the PDB ESCs and battery/voltage measurements.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg3AaN1QIBCJ_Qgq2UAYB1KOw8_n2TxAxBvztM5ymtgRo4SFlY0OC6QO2cpz6qf7LGPBU1-tJdhMwwRzbZayYY0sW3ZnyTcu9xDr8EMJLPh8Mf8vOWbvY2XQw_znLikgzvLjhczYXJ2ltw/s1600/boards+installed.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg3AaN1QIBCJ_Qgq2UAYB1KOw8_n2TxAxBvztM5ymtgRo4SFlY0OC6QO2cpz6qf7LGPBU1-tJdhMwwRzbZayYY0sW3ZnyTcu9xDr8EMJLPh8Mf8vOWbvY2XQw_znLikgzvLjhczYXJ2ltw/s1600/boards+installed.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And then covers placed over the boards and PDB to keep the battery away from them.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhmn3OBfnv2i1eSXFRuY_4WPue4_qQ_FAw-WJFVFpGtlJbvvSzs3Lgp2GyfKhgxKI_OdXYYs5qmTtrcltNvTFVQ9wt6E8S2PZTgtoC5Z7NavZVtNd8reEk3csRnWIEYVLmjFYYLLfSCvPY/s1600/boards+covered.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhmn3OBfnv2i1eSXFRuY_4WPue4_qQ_FAw-WJFVFpGtlJbvvSzs3Lgp2GyfKhgxKI_OdXYYs5qmTtrcltNvTFVQ9wt6E8S2PZTgtoC5Z7NavZVtNd8reEk3csRnWIEYVLmjFYYLLfSCvPY/s1600/boards+covered.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And here is the integrated gimbal on the front with the SparkyBGC sensor mounted to the top.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgoOqPk6k-9Y0_dVQLvaefKKC7K1xPlprrpvZ8bpQFHCH3MKbJvehqtdO_3jHj02vvE9LY1iDfuiiMVYIEMXVyNLzziytpdPEMwPTDq5j8SqN7Ol3OOphJLZ0iFaq0csFFVqkW3ISSmnEE/s1600/gimbal.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="263" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgoOqPk6k-9Y0_dVQLvaefKKC7K1xPlprrpvZ8bpQFHCH3MKbJvehqtdO_3jHj02vvE9LY1iDfuiiMVYIEMXVyNLzziytpdPEMwPTDq5j8SqN7Ol3OOphJLZ0iFaq0csFFVqkW3ISSmnEE/s1600/gimbal.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3>
<b>Camera Control</b></h3>
<div>
The camera is stabilized via the SparkyBGC board. This communicates via CAN (which is a nice high speed bidirectional bus) to the Sparky2 board. This allows information from Sparky2 to control the camera angle. For example, you can set it up to only correct part of the flight controller roll which creates a smooth video that still shows some of the action. You can also set up the pitch to be controlled via a slider or switch from the transmitter that is relayed via the flight controller.</div>
<div>
<br /></div>
<div>
Finally, you can also use the Tau Labs Android GCS to talk to the flight controller and pass the location of the phone or tablet. The FC then calculates the heading and camera pitch to focus on that point of interest and tracks it. This doesn't work perfectly because the phone GPS is sometimes noisy or slow, but generally works quite well. You can also work around this by directly dragging and moving the POI location rather than tracking the tablet.<br />
<br /></div>
<h3 style="text-align: left;">
Final Assembly and Flights</h3>
<div>
Here you can see it all put together.</div>
<div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: left;">
<br /></div>
<div style="text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiI8YLjtyE8wIyHs_MAzyCiXoc0RA62Mx0TL_9JqbA3y8xRl6mqgCSs6ZKRPfyxTiCGPduXPlROcSPczB72UUNeh_kB8gASyO3OJwvVLDrJQqQ-9BhspvftRy-n2TpMyuNScdgLOASKLeU/s1600/gps.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiI8YLjtyE8wIyHs_MAzyCiXoc0RA62Mx0TL_9JqbA3y8xRl6mqgCSs6ZKRPfyxTiCGPduXPlROcSPczB72UUNeh_kB8gASyO3OJwvVLDrJQqQ-9BhspvftRy-n2TpMyuNScdgLOASKLeU/s1600/gps.jpg" width="320" /></a></div>
<div style="text-align: center;">
<br /></div>
</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj6gPIjz58zgwu5wHLpRP2LluQa1hODdDxEmEz21BErQL4Mp6VA41oKNXRq2O6uAcvDQjul0IC2J2QB30GFJGu6kmbOQzcS0fiJOYJ9YQmCnR399VZHpDL-KmZOccbMt7aQQR0Dne7eeP8/s1600/closed.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj6gPIjz58zgwu5wHLpRP2LluQa1hODdDxEmEz21BErQL4Mp6VA41oKNXRq2O6uAcvDQjul0IC2J2QB30GFJGu6kmbOQzcS0fiJOYJ9YQmCnR399VZHpDL-KmZOccbMt7aQQR0Dne7eeP8/s1600/closed.jpg" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh_vdHSbBe_O9rQUXweduDT-06XLtlQ1wW17YxyYM4J5VjNm-ekKRqCtdjVGiTc1h7A8ChyEclRfqCWkoj_1vZ4-q-DUm96JFZc_nqVelq6iTfH1n87QxAvfz6fG3zgFTjhK1MvEwcqw-U/s1600/front.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh_vdHSbBe_O9rQUXweduDT-06XLtlQ1wW17YxyYM4J5VjNm-ekKRqCtdjVGiTc1h7A8ChyEclRfqCWkoj_1vZ4-q-DUm96JFZc_nqVelq6iTfH1n87QxAvfz6fG3zgFTjhK1MvEwcqw-U/s1600/front.jpg" width="320" /></a></div>
<div>
<br />
And with an updated canopy that has smoother lines:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjErQ0Vy3kDI76BMnBFN0KbtpAY67NuZoRwJXseHVpdipeHLbMNcjNIz7uDS5VOn40O2yC1jYwNj5aWG1VtnvZl7PhO7WaxQtduSyqDVC5cliubmwVEbx0gZZJFhGnYpCwfcNZ1GfpESbM/s1600/IMG_20141103_112228.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="272" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjErQ0Vy3kDI76BMnBFN0KbtpAY67NuZoRwJXseHVpdipeHLbMNcjNIz7uDS5VOn40O2yC1jYwNj5aWG1VtnvZl7PhO7WaxQtduSyqDVC5cliubmwVEbx0gZZJFhGnYpCwfcNZ1GfpESbM/s1600/IMG_20141103_112228.jpg" width="320" /></a></div>
<br />
Here it is being used to do some simple point of interest tracking to my phone, being held by my lovely assistant.<br />
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/110206635" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<h3 style="text-align: left;">
Crashing :D</h3>
<div>
This quad got plenty of crashing :). You can see in the long video at the end where I plowed it into the ground upside down. The result was two broken arms:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjwlZosx-3QhvBxbpFDvgrXQzGqJyky_qsnt6ktqV4p0AWYKHIXYR2FeWpC76KKDym3Z1W-NKq8g2HWJac5np0znje2_lv3K5XX6-ukJwWJGGP_KWWM_kJPVW_JTFL6mO1dObjlVIs1QiU/s1600/Screen+Shot+2014-11-02+at+3.38.08+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="200" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjwlZosx-3QhvBxbpFDvgrXQzGqJyky_qsnt6ktqV4p0AWYKHIXYR2FeWpC76KKDym3Z1W-NKq8g2HWJac5np0znje2_lv3K5XX6-ukJwWJGGP_KWWM_kJPVW_JTFL6mO1dObjlVIs1QiU/s1600/Screen+Shot+2014-11-02+at+3.38.08+PM.png" width="320" /></a></div>
<br />
I also had a good time taking it out this weekend. My friends dog also absolutely loved chasing it (he loves running). I'm still not the best at flying backwards at high speeds while leading a dog, though. One of the earlier flights I caught a tree enough to unscrew a prop nut. It landed flat enough and unharmed. Unfortunately despite ten minutes of a number of us looking, we couldn't find the nut and I foolishly forgot spares.</div>
<div>
<br /></div>
<div>
I turns out you can use a spacer screwed on with camping tongs to get airborne again :D</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgfcTIHbgNjjTR2qdW2uHq1ivQu9uyruHq1O0Muz-dbJWDpYa8v05hbI0T3-leP4Q9DU7YVKH5uDcvhay5jBUk97c2zA80miBQ_W8kHgrcoqSGAwmY0qCGYEJJj9FhNIBwBIZ9QbNSI2BA/s1600/IMG_20141101_174146_small.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgfcTIHbgNjjTR2qdW2uHq1ivQu9uyruHq1O0Muz-dbJWDpYa8v05hbI0T3-leP4Q9DU7YVKH5uDcvhay5jBUk97c2zA80miBQ_W8kHgrcoqSGAwmY0qCGYEJJj9FhNIBwBIZ9QbNSI2BA/s1600/IMG_20141101_174146_small.jpg" width="320" /></a></div>
<div>
<br /></div>
<div>
Unfortunately, that only lasted too long until I backed into another tree, this time much higher...</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjhHwOimI2dUxwg2p_M3Xys-3eEWFxQTsZmTyAoiZxYQNT9onCwrlnoicaKR7OExWb_Qz5T-Ux3Uu8HwCG9wTgGwFQr1KUqGpylE5HsugSPB9oVVfFWDfnJMcf0IeWHjBFS9u3MtSwYshw/s1600/IMG_20141101_180642_small.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjhHwOimI2dUxwg2p_M3Xys-3eEWFxQTsZmTyAoiZxYQNT9onCwrlnoicaKR7OExWb_Qz5T-Ux3Uu8HwCG9wTgGwFQr1KUqGpylE5HsugSPB9oVVfFWDfnJMcf0IeWHjBFS9u3MtSwYshw/s1600/IMG_20141101_180642_small.jpg" width="320" /></a></div>
<div>
<br /></div>
<div>
So back to the 3D printer. I think I might try and smooth some of the curves in the canopy anyway, and possibly reinforce the walls some more.</div>
<div>
<br /></div>
<div>
<br /></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com197tag:blogger.com,1999:blog-1759046512792102553.post-2937794207032755592014-10-31T13:05:00.000-07:002014-11-04T05:52:58.394-08:00Gemini (powered by Tau Labs) tear down and review<div dir="ltr" style="text-align: left;" trbidi="on">
One of the more exciting added in the <a href="https://github.com/TauLabs/TauLabs/releases/tag/20141026">latest Tau Labs release</a> is support for the Colibri flight controller. This is the flight controller that is used in the <a href="http://www.team-blacksheep.com/products/prod:gemini">Gemini</a> hexcopter (designed in collaboration with an awesome designer William Thielicke of <a href="http://shrediquette.blogspot.com/p/shrediquette-gemini.html">shrediquette fame</a>). I've been lucky enough to have access to a Gemini for several weeks now for development and wanted to write up my thoughts.<br />
<br />
Here is a video of me flying which also shows you the ground station and some chase shots. It uses some early PID settings and is a bit wobbly.<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/110564442" webkitallowfullscreen="" width="500"></iframe>
<br />
<br />
<div style="text-align: left;">
And here is a video from TBS that is better tuned and flies more smoothly:</div>
<br />
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/110831709" webkitallowfullscreen="" width="500"></iframe></div>
<br />
The short version is <b>impressive.</b> What impresses me most is the level of <i>system integration</i> involved. This is what you get when you design the whole system for a purpose, rather than taking parts and figuring out how to put them together. In a way, this is the type of achievement we had hoped people would do from day one with CopterControl - creating something that is elegant and easy to fly.<br />
<br />
<h3 style="text-align: left;">
Unboxing</h3>
<div>
Ok, this is the first time I have had a real "unboxing" experience with a multirotor. Probably because I never get prebuilt systems, but this was great. It comes in a slick traveling case, nicely embossed with a TBS logo and a hexcopter symbol.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjeEMoUVK5ghxGMun9-92SfwldR3CLv-gaR0bNlkD5G3l8Sm5jVFH-P8IufIADfvDYl1jzWX3LHCtH9QCalegSpkU-8PzEnd6JOX8W9U-zwRZDZuJYLKTujmmn8l0OQLwPcuqx6cIzDafs/s1600/case.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjeEMoUVK5ghxGMun9-92SfwldR3CLv-gaR0bNlkD5G3l8Sm5jVFH-P8IufIADfvDYl1jzWX3LHCtH9QCalegSpkU-8PzEnd6JOX8W9U-zwRZDZuJYLKTujmmn8l0OQLwPcuqx6cIzDafs/s1600/case.jpg" height="231" width="320" /></a></div>
<br />
Inside I found Gemini, spare props and the FPV antenna. The whole system was already wired up and ready to go (except for the receiver). I'm assuming the production versions will come enclosed in the canopy, but mine did not have one.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg-Q7UP7fK6XyP9yvOVeLcLGurcRIOyZcmFWtkhtsupgU2IIEG2Yspb9bmVvOKCg5N0U1RAyDbGRYEqbkZDd5fV4jmc2r3PBsJKPRlLDHaba_bss0ha5xtV2ZexVfvlt5LAiMAcnV2Mm9A/s1600/opencase.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg-Q7UP7fK6XyP9yvOVeLcLGurcRIOyZcmFWtkhtsupgU2IIEG2Yspb9bmVvOKCg5N0U1RAyDbGRYEqbkZDd5fV4jmc2r3PBsJKPRlLDHaba_bss0ha5xtV2ZexVfvlt5LAiMAcnV2Mm9A/s1600/opencase.jpg" height="257" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="text-align: left;">
Frame</h3>
<div>
So here you see it! A very compact elegant setup.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi32eKbILDVkPJt5pzruDZBo-cTylUQGpgBZ1mBdu8S1idAL6O-8rXYbRgDXED7Iv4N2VYet-8ZiadJMzYTB0WfPUGBJESLRyOtwJkL1_r8GKtmQgfnMQG8nEZAKyvj6UQIJAP_PnLGkrg/s1600/gemini.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi32eKbILDVkPJt5pzruDZBo-cTylUQGpgBZ1mBdu8S1idAL6O-8rXYbRgDXED7Iv4N2VYet-8ZiadJMzYTB0WfPUGBJESLRyOtwJkL1_r8GKtmQgfnMQG8nEZAKyvj6UQIJAP_PnLGkrg/s1600/gemini.jpg" height="253" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And a side view shows the tilted motors. This is really well done with the frame material actually conformed to hold the motors at the right angle. I dread to think the cost of setting up prototypes of this. Despite the shaping, the frame feels <i>incredibly</i> strong.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div style="margin-left: 1em; margin-right: 1em; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjZqrusAhgKwtJ_ZgGFPjhXcOS430wm5o2cZZBa1aaHnBrGT3PMXJ0V_jD28YRLN1KF7DnGKqk09iux4jx9US-LZ3BJY4_Dh0lnoC3QKhwugWspEkovYzD0KW-AYLb7a0eiao_VsEWE-d8/s1600/motors.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"></a><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjZqrusAhgKwtJ_ZgGFPjhXcOS430wm5o2cZZBa1aaHnBrGT3PMXJ0V_jD28YRLN1KF7DnGKqk09iux4jx9US-LZ3BJY4_Dh0lnoC3QKhwugWspEkovYzD0KW-AYLb7a0eiao_VsEWE-d8/s1600/motors.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjZqrusAhgKwtJ_ZgGFPjhXcOS430wm5o2cZZBa1aaHnBrGT3PMXJ0V_jD28YRLN1KF7DnGKqk09iux4jx9US-LZ3BJY4_Dh0lnoC3QKhwugWspEkovYzD0KW-AYLb7a0eiao_VsEWE-d8/s1600/motors.jpg" height="102" width="320" /></a></div>
<br />
<div>
<br /></div>
<div>
The motors are tiny little T-Motors. Basically the size of my thumb. What is really nice is that the ESC wiring is integrated into the frame. This means no confusing which lead is which and no ugly wires to try and hide. You can also see the little OrangeRX satellite receiver I'm using in this shot. Also, the mount for the mobius camera is evident and hanging from the frame by four vibration damping mounts (with the tie wrap I use to secure it).</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiBes5DQ8wgKN0sXgNpt9vcX4n5S59vqTDf9D0IGVOuZBeAWG-oVQyHNGukbqbS4iKjlugwL3ZngCsYiue3q06P_tMnB9MZ0UE_5D9w8X5bh16DgsyIEGlbuwQ3rBaNCxs5zH4RCELlxpI/s1600/back.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiBes5DQ8wgKN0sXgNpt9vcX4n5S59vqTDf9D0IGVOuZBeAWG-oVQyHNGukbqbS4iKjlugwL3ZngCsYiue3q06P_tMnB9MZ0UE_5D9w8X5bh16DgsyIEGlbuwQ3rBaNCxs5zH4RCELlxpI/s1600/back.jpg" height="265" width="320" /></a></div>
<div>
<br /></div>
<div>
I also really like the elastic strap for mounting the battery. In the early photo you can see there is a little plastic stick through the ends of it on the top to secure it, rather than wrapping it around everything. Attention to detail is obvious in this design.</div>
<div>
<br />
The arms also come with vibration dampeners between the frame and the motor mount. This two stage vibration isolation (arm and then at camera) works really well for larger frames and I think contributes to the video quality I'm getting. Plus higher RPM motors just produce much less jello.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjL2KFZj9GRahdTBe9TPwXsJX1FsABGnZDmzxNhYBU9PicJT0tglgu_aV4LWsBu5l4oT2MEW5VG_IRLfZuwp2dYEPpUF9xybDdvyoEiFBU7Tb3dEgCMsDrObLesUv5aVgTxX_d-JqF-GfM/s1600/IMG_20141030_230552.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjL2KFZj9GRahdTBe9TPwXsJX1FsABGnZDmzxNhYBU9PicJT0tglgu_aV4LWsBu5l4oT2MEW5VG_IRLfZuwp2dYEPpUF9xybDdvyoEiFBU7Tb3dEgCMsDrObLesUv5aVgTxX_d-JqF-GfM/s1600/IMG_20141030_230552.jpg" height="292" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<br /></div>
<div>
You can also see that the motors attach to the frame wiring via JST connectors. Again, a nice detail focus was keeping the pinout the same for each motor and handling the lead swapping in the PCB layout. This makes sure no one can get confused. I will comment that the final version uses the <b>opposite</b> motor direction as our default orientation, so if you are configuring from scratch one must remember to reverse the motor directions in software. However, most people will use the configuration file provided by TBS and not need to deal with this.<br />
<br /></div>
<h3 style="text-align: left;">
Flight Controller and electronics</h3>
Colibri is a really small flight controller designed by Team Black Sheet that takes the <a href="http://www.quantec-networks.de/shop/en/quanton/1/quanton-flight-control-rev.-1">Quanton</a> design (by lilvinz of Quantec) and shrinks it down. TBS did the right thing from day 1 here - they approached Lilvinz and asked to make a derivative of his CC-BY-SA-NC design and he acquiesced. This is open source working the right way!<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgNGGYE0zur2QmzE2fnYt1vD2G9e22ZFoF7F2KJ1TsBG5k88YJe-hpfsNBgjzyh_f44L22bVqM5IC6Yc0PbVsMlaEKczeHXdn7XNSUUjHra-0Ecz_UGJdoV02v5qMY1aFzyDdgojGszG0c/s1600/IMG_20141027_111901.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgNGGYE0zur2QmzE2fnYt1vD2G9e22ZFoF7F2KJ1TsBG5k88YJe-hpfsNBgjzyh_f44L22bVqM5IC6Yc0PbVsMlaEKczeHXdn7XNSUUjHra-0Ecz_UGJdoV02v5qMY1aFzyDdgojGszG0c/s1600/IMG_20141027_111901.jpg" height="239" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2l4Y5wd7bC371iJ2IYBjrWMHoIwiC5aqs0nkh988LGOJbk0ts3VghR0XlQbfGpltAu3eka0Rd_Z9Vn30BWQw8cHusBlCoGafujJNFSbBfKirsJaIjHOV5caS4cxvItIa30ealHvKBDrw/s1600/IMG_20141027_111919.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2l4Y5wd7bC371iJ2IYBjrWMHoIwiC5aqs0nkh988LGOJbk0ts3VghR0XlQbfGpltAu3eka0Rd_Z9Vn30BWQw8cHusBlCoGafujJNFSbBfKirsJaIjHOV5caS4cxvItIa30ealHvKBDrw/s1600/IMG_20141027_111919.jpg" height="258" width="320" /></a></div>
<br />
As you can see the board uses microtouch connectors. It is a really small design, but still packs in the full suite of barometer, magnetometer, 3-axis accel and 3-axis gyro and flash. The breakout headers give access to all the Quanton IO so in principle it supports 8 channels in and out, as well as a number of serial and I2C ports. Here it is compared to a quarter. Sorry non-Americans, this might not mean much to you.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg9XhsbHUKBBHPaQYuGxpMHJtp5o-i5IIhAH9PgketFwcLnFN_1VbYcZtMf8KejTCGbpWdYeKl1c2ejJ7KjHqih03NlV1rEpcTs7czoXMkfguSwTUPCWj83e3PMqj2QHaAVWh0OakS9Svk/s1600/size.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg9XhsbHUKBBHPaQYuGxpMHJtp5o-i5IIhAH9PgketFwcLnFN_1VbYcZtMf8KejTCGbpWdYeKl1c2ejJ7KjHqih03NlV1rEpcTs7czoXMkfguSwTUPCWj83e3PMqj2QHaAVWh0OakS9Svk/s1600/size.jpg" height="171" width="200" /></a></div>
<br />
The approach of a high-density powerful flight controller is not ideal for end users making their own frames, but is absolutely perfect for this custom, focused, miniatured design that doesn't want to sacrifice features. Kudos to TBS for the work required to miniature this design so much.<br />
<br />
This board then sits on an IO board that breaks out the wire from Colibri for use on Gemini. This IO board has the 6 bulletproof ESCs, an receiver port breakout (supports PWM, PPM, DSM2/X, SBus) and a second serial port which can be used for telemetry or GPS. You can see the wire going to my OrangeRX satellite in the lower right.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgdgS3lJ97jv-uWLmq8AVgRB4jKDccb9Xkf5cENobFHujO3ouV5_hZEOpjvZ87m0WL6tRn5vV_kmzpsuDqHQRdFRGru4ZgpgHYGzlIuPfGh9DvT75VK5wKE0mGqGIwFnAIvxcF4G06LqoI/s1600/electronics.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgdgS3lJ97jv-uWLmq8AVgRB4jKDccb9Xkf5cENobFHujO3ouV5_hZEOpjvZ87m0WL6tRn5vV_kmzpsuDqHQRdFRGru4ZgpgHYGzlIuPfGh9DvT75VK5wKE0mGqGIwFnAIvxcF4G06LqoI/s1600/electronics.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Here is a closer front view of the electronics. You can see the TBS UNIFY 5.8 GHz 200mW transmitter connected to the TBS Core and the camera. It is hard to appreciate in this photo, but all of this is mounted as a plastic sub assembly to hold and mount the camera, support the vibration damping to the mobius, and provide the vertical support for the VTX. Again, a nice custom solution that got everything needed into a compact space.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi2obWFF9sBkrCJ3onNd5B6N5kCx-dUcttiEOpAdTusxNluWnR1LuUgULO9n6e2XbVwiO7ysWPN3uIEkyqmtB3FKQ6wFEZhU4h7Rl7n2iAwlN3P0n_DrRqIAVO980eLbHNaWePuwx00CRY/s1600/electronics_front.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi2obWFF9sBkrCJ3onNd5B6N5kCx-dUcttiEOpAdTusxNluWnR1LuUgULO9n6e2XbVwiO7ysWPN3uIEkyqmtB3FKQ6wFEZhU4h7Rl7n2iAwlN3P0n_DrRqIAVO980eLbHNaWePuwx00CRY/s1600/electronics_front.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And here are the electronics viewed from the back. This gives you another nice view of the 6 ESCs in parallel. The board mount approach is really space efficient and again contributes nicely to the compactness of the design. </div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCsKkW-0ol5SfkTH70DAj4TH5kyH5EM0KLIEtLo35m_R2ZPyWiMvTlnpmGSLmnilsVcwxcAws49Jr99Nh585wuRR1zrWsM5csVAOIx4RVGHLyjztwaf06T98d-CyENyqDTBmrxH8HdAbk/s1600/electronics_back.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCsKkW-0ol5SfkTH70DAj4TH5kyH5EM0KLIEtLo35m_R2ZPyWiMvTlnpmGSLmnilsVcwxcAws49Jr99Nh585wuRR1zrWsM5csVAOIx4RVGHLyjztwaf06T98d-CyENyqDTBmrxH8HdAbk/s1600/electronics_back.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
And lifting up Colibri reveals some nice foam used to protect the barometer from turbulence and get a clean measurement. The flight controller makes a very nice firm fit on these headers, despite the number of times I've had it on and off.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgLgKVn0RFRTLeV118YgMewFRpe93MZfNWRV5ZtA1Ynr1231R2URQrNDe_dObiCIFrXRveRX68-sshPMb4tFTVLmPRjISIuL6gM6MmWlh68cIO1ttDJ1MmVjbq00pD-G1b5AZYIMl63cY8/s1600/no_colibri.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgLgKVn0RFRTLeV118YgMewFRpe93MZfNWRV5ZtA1Ynr1231R2URQrNDe_dObiCIFrXRveRX68-sshPMb4tFTVLmPRjISIuL6gM6MmWlh68cIO1ttDJ1MmVjbq00pD-G1b5AZYIMl63cY8/s1600/no_colibri.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And finally the whole IO board can be lifted up to show the ESC connections from the bottom. The connections to the main frame is done through a series of standard 100-mil spaced headers. This routes the cables from the ESCs into the main frame wiring, as well as providing power to the IO breakout board.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
You can see in this photos the soldered connections to the ESCs. It will be interesting to see how easy that is to remove and replace. The board mounts protrude 1 or 2 millimeters past the board which might make it easier to break the connection. However, it might be that a bit of flux and braid are required to really free them up. Either way, it wouldn't be worth the increased height and weight to have a connector for each ESC.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh6_xe3XzJeV-NOhnH1dkyakQQkDMSCnFtlPWJGHSE4iSt0YLcef951ugF-RZE3wRok2PZlhnf8ZRUpiVYuthxEX8uJDbgPHv91zee3FdvTzmXp7eSs9uR2tysXhzg73TIOVlGYztTp54Y/s1600/io_board_up.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh6_xe3XzJeV-NOhnH1dkyakQQkDMSCnFtlPWJGHSE4iSt0YLcef951ugF-RZE3wRok2PZlhnf8ZRUpiVYuthxEX8uJDbgPHv91zee3FdvTzmXp7eSs9uR2tysXhzg73TIOVlGYztTp54Y/s1600/io_board_up.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Finally the integrated wiring into the frame mentioned above is really nice. I'm not entirely sure the process that went into making a PCB laminate and then applying it to the frame with the twisted motors. The motor wires do run on straight segments of the frame, so perhaps that helped. Anyway, I don't envy the cloners who are trying to rush an mimic this process.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjWrhdvuHSKDjM8LhH3KK_NCto-JS_HWqiue-iiYMebB6v1wBunSFkRGx36PFAROuJ44CG34gYGM2Qi0GbajxUyNLpP82_P1j_N1rW9Ts6DMoQ5-07InXuAlfjpFePMGRCm7SQsIJ73nC4/s1600/wiring.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjWrhdvuHSKDjM8LhH3KK_NCto-JS_HWqiue-iiYMebB6v1wBunSFkRGx36PFAROuJ44CG34gYGM2Qi0GbajxUyNLpP82_P1j_N1rW9Ts6DMoQ5-07InXuAlfjpFePMGRCm7SQsIJ73nC4/s1600/wiring.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="clear: both; text-align: left;">
Crash resistance</h3>
<div>
Well I've only flown this for an hour or two. However, I have already done a good job of crashing it. One thing I'm less used to (flying mostly quads) is that it does a great job of crashing into things. I flew into a tree while in altitude hold mode and the flight controller totally recovered and had me floating in clear sky. </div>
<div>
<br /></div>
<div>
I tried teaching a friend to fly it under a tree and only lost a prop.</div>
<div>
<br /></div>
<div>
I flew into a tree about 10 feet up and just had to pick it up and replace a prop.</div>
<div>
<br /></div>
<div>
Finally, I flew it at full throttle (probably 35+mph) into the bottom side of a bridge. Completely misjudged the height by a foot. I really expected to be picking up pieces, but in the end nothing important was damaged. The bolts holding the front two motors sheared. The frame was entirely intact. All electronics are ESC traces are good. Even the motor connectors on the frame are still attached. The plastic assembly that holds the flight camera either needs some glue or replacing. Overally, I was shocked by how minimal the damage was.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgBxT8boTMtm0EI1UencVLBheeDDqYp9tqpEDZ7Ai2V6rlHkscsWKIKqhQa2A-W4hnB_XnZU310IzcNIwnN3zejtDTLDzMKaMRaJzbtfhLADbwsLUPngjnNcHQmc5jZRhbeLYztHt_GBe4/s1600/crash.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgBxT8boTMtm0EI1UencVLBheeDDqYp9tqpEDZ7Ai2V6rlHkscsWKIKqhQa2A-W4hnB_XnZU310IzcNIwnN3zejtDTLDzMKaMRaJzbtfhLADbwsLUPngjnNcHQmc5jZRhbeLYztHt_GBe4/s1600/crash.jpg" height="240" width="320" /></a></div>
<div>
<br /></div>
<h3 style="text-align: left;">
Summary</h3>
<div>
Ultimately, I am very impressed with this frame. There are a lot of fairly novel (if not entirely unique) concepts here that aren't in many frames. The integrated wiring with the frame as a PDB is pretty uncommon in anything this size (obviously things like Crazyflie have done it) and makes the lines really slick looking, not to mention aerodynamic. The twisted motors I first saw in William Thielicke's shreddiquette designs and they have done a nice job of taking that into a custom warped frame. </div>
<div>
<br /></div>
<div>
The level of integration with the tiny Colibri flight controller, IO board that with integrated ESC connections and then the breakout into the frame is what really impresses me. This was all made custom for Gemini and just makes the whole thing light, compact, and probably quite robust to crashing. I also haven't see this approach to integration in <b>any</b> frame running open source software (maybe some proprietary frames are similar?).</div>
<div>
<br /></div>
<div>
A big congratulations to Team Black Sheep for making an awesome product and I'm glad they wanted to use Tau Labs to really get the most out of it. I'm sure this will be extremely popular with pilots and hopefully as a trickle down effect we will get some people active in the TL community.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com10tag:blogger.com,1999:blog-1759046512792102553.post-32154380001556293982014-10-25T17:38:00.000-07:002014-11-02T15:59:41.174-08:00Reflecting on four years of development<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
As I was digging through my bins of parts to find an original analog CopterControl, I was struck by how much work and how many things we have designed with both Tau Labs and originally with OpenPilot over the last 5 years. I thought I'd take a wander down memory lane and look at some of the boards (released and unreleased).<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhpEPEta6TpOIZbEfCxqsQ5VsB8cGaQkddYPLntpFzvr0q8gSBpi0YVEVFLLWWEViqu4VF8jjh4gD0xHxw2o05ZoR5xopqIXlJbneFi5Bp107CuMUdSGMWXG1XfhTQkO6wJIMD1XRIL4KY/s1600/IMG_20141025_192038.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhpEPEta6TpOIZbEfCxqsQ5VsB8cGaQkddYPLntpFzvr0q8gSBpi0YVEVFLLWWEViqu4VF8jjh4gD0xHxw2o05ZoR5xopqIXlJbneFi5Bp107CuMUdSGMWXG1XfhTQkO6wJIMD1XRIL4KY/s1600/IMG_20141025_192038.jpg" height="347" width="400" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;"><span style="font-size: small; text-align: left;">MainBoard, AHRS, CopterControl, CC3D, Revolution, RevoMini, Freedom, Sparky, Sparky2, SparkyBGC, TauLink, OSD</span></td></tr>
</tbody></table>
<br />
<h3 style="text-align: left;">
Mainboard and AHRS (2010)</h3>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjc_Sdb3XMjppeSPjgR2H86lTWBnocgvVbtqRJ84WitvFVQXk-8uG-qtC9c2kbQPmhwPTvlAwmAvF3C-Bxo1AUQ_FaEs15pG100mFM8tn06EtiaiJaoZ1M2xfV7Tm_-Prw8LzOKMNpTjQY/s1600/IMG_20141025_155643.jpg" imageanchor="1" style="clear: right; float: right; margin-bottom: 1em; margin-left: 1em;"><br /></a><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgm8vUMoNJ96rB6cSxpwwTCH7LZWhqCtUtnitZagYJtItUkjXDHpZN5953GDBKUXSnopMNB50Hv2f0i1eW_Gujn9wqRCHtRcqmzCbMj95Fag88hkCc8eadmhEljrCqY17TGxKtGC4tWEMQ/s1600/IMG_20141025_155244.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgm8vUMoNJ96rB6cSxpwwTCH7LZWhqCtUtnitZagYJtItUkjXDHpZN5953GDBKUXSnopMNB50Hv2f0i1eW_Gujn9wqRCHtRcqmzCbMj95Fag88hkCc8eadmhEljrCqY17TGxKtGC4tWEMQ/s1600/IMG_20141025_155244.jpg" height="293" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
And a closeup of the INS (slightly different revision - BMP085 and ports for GPS moved to AHRS).</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjc_Sdb3XMjppeSPjgR2H86lTWBnocgvVbtqRJ84WitvFVQXk-8uG-qtC9c2kbQPmhwPTvlAwmAvF3C-Bxo1AUQ_FaEs15pG100mFM8tn06EtiaiJaoZ1M2xfV7Tm_-Prw8LzOKMNpTjQY/s1600/IMG_20141025_155643.jpg" imageanchor="1" style="clear: right; margin-bottom: 1em; margin-left: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjc_Sdb3XMjppeSPjgR2H86lTWBnocgvVbtqRJ84WitvFVQXk-8uG-qtC9c2kbQPmhwPTvlAwmAvF3C-Bxo1AUQ_FaEs15pG100mFM8tn06EtiaiJaoZ1M2xfV7Tm_-Prw8LzOKMNpTjQY/s1600/IMG_20141025_155643.jpg" height="281" width="320" /></a></div>
<div>
<br /></div>
<div>
These boards were designed by Angus Peart, one of the co-founders of OpenPilot and also a founder of the Omniloco foundation which is the foundation behind TauLabs. They were painstakingly hand soldered by David Ankers, the other co-founder of OpenPilot. The F1 processors at the time were not (and still aren't) powerful enough to run a full suite of algorithms for navigation, so the decision was made to have one board (AHRS) acquire all the sensor data and fuse it (run the INS) and another (Mainboard) to handle all the control code and input/output. The sensors were analog </div>
<div>
<br /></div>
<div>
The fusion algorithm is one we still use, an INSGPS algorithm written by Dale Schinstock. A lot of my original work on the OpenPilot project was originally getting this fusion algorithm working with our sensors and behaving well, as well as the original control code to stay in the air.<br />
Here is the very first stabilized flight using the OpenPilot software.<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/14679877" webkitallowfullscreen="" width="500"></iframe></div>
<br />
And the first flight of a quadcopter with our hardware. Unfortunately, I had no idea how to fly one so it simply floated into a tree...<br />
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/15057610" webkitallowfullscreen="" width="500"></iframe> </div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: left;">
Then there was the aborted attempt to get more power from the INS. This used the F2 series of CPUs which had a bit more power than the F1. You can see little bridges of wire where we didn't quite account for the CPU differences and I had to hack it up to get it running. Where there is a will, there is a way. Ultimately this was one of many boards that were made but didn't become a viable product. I think we also did a number of sensor trials on these boards because I have some lying around with various sensors like BMA180. Lots of work writing and testing those drivers and getting the data to ultimately not use them. Still, gotta try it to know which is best.</div>
<div style="text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhZ00ojcySAxzmV0CMJSiKzrcJ5euuy4gSy32D7Pi9xsAxFhn40VM-qYkyr9SWXOGhcH-CPtGJ7vzEm2mCLyFp290yPqf3uu3noFm2H_xSlJ0_Iu5G9M3ufKJYRqeGGqQB1orpERNML-6w/s1600/IMG_20141025_155902.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhZ00ojcySAxzmV0CMJSiKzrcJ5euuy4gSy32D7Pi9xsAxFhn40VM-qYkyr9SWXOGhcH-CPtGJ7vzEm2mCLyFp290yPqf3uu3noFm2H_xSlJ0_Iu5G9M3ufKJYRqeGGqQB1orpERNML-6w/s1600/IMG_20141025_155902.jpg" height="295" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
The AHRS+Mainboard was ultimately a pretty powerful setup, although programming and syncing data between the two boards was a real PITA. PT_Dreamer did an impressive job of writing the bootloader so it would upgrade both boards at the same time. We even managed to get some demonstrations of position hold working on this hardware, around three years ago now at our developer retreat in Portugal (oh fun times: https://vimeo.com/23865574.</div>
<br />
<h3 style="text-align: left;">
CopterControl (early 2011)</h3>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhsgmTiYt9yeeWC8cflvt2AQlpkurxgdVkmscXMyY2C41OkN0iUpQpV4lq6mHt_FbPGLdrFAm-NTNmstmMMrG10dJHeKc9nrhGiuj3Hfyp7y7d8TJgixQ36f4Md8_DW48MZ-GDkNraq9Go/s1600/IMG_20141025_163619.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhsgmTiYt9yeeWC8cflvt2AQlpkurxgdVkmscXMyY2C41OkN0iUpQpV4lq6mHt_FbPGLdrFAm-NTNmstmMMrG10dJHeKc9nrhGiuj3Hfyp7y7d8TJgixQ36f4Md8_DW48MZ-GDkNraq9Go/s1600/IMG_20141025_163619.jpg" height="293" width="320" /></a></div>
<div>
<br /></div>
<div>
This board was designed by David with help from Pip (I think) and took the AHRS designed by Angus and added the input output ports to it. The processing / memory limitations of the F1 were still there, but this board was meant to be a stripped down user-oriented version of the original hardware capable of stabilizing a quad or plane. It used the same analog invensense sensors as the AHRS. These were fairly good sensors in terms of noise performance, but their drift (and especially zero bias at powerup) were quite problematic. It had a 3-axis gyro and 3-axis accelerometer.<br />
<br />
Of course, here is the mandatory first flight video:<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/19612039" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Because of the limited processing power of CC3D, the INS algorithm could not run without negatively affecting the flight performance. I designed a complementary filter implementation (based on Mahoney's papers) that was quite efficient and allowed us to process data at several hundred Hz. This really improved the flight performance, and having everything on one controller really improved the latency.<br />
<br />
In retrospect, I can't decide if this was a good or bad direction for the project. In a lot of ways, it created a several year distraction from a lot of autonomous functionality. At the time we were probably comparable with Arducopter in terms of PH and navigation, but ended up quite a distance behind.<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjLDl3iAIx3oaS7P-rubySiadtXxgr2FaRyinYSQWdhU7XmzMocRRRDmUDrKC7CrUOgvoBIXRiC4Ab5n5r0vDEkw7yBI1VS-HMU15NG0WuuXyhQvsrre6HPjgtCWVtCA1ajMT7k5LkT3jA/s1600/IMG_20141025_160318.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjLDl3iAIx3oaS7P-rubySiadtXxgr2FaRyinYSQWdhU7XmzMocRRRDmUDrKC7CrUOgvoBIXRiC4Ab5n5r0vDEkw7yBI1VS-HMU15NG0WuuXyhQvsrre6HPjgtCWVtCA1ajMT7k5LkT3jA/s1600/IMG_20141025_160318.jpg" height="161" width="200" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
This little mag/pressure sensor was an attempt to bring more functionality to CopterControl (and CC3D) but ultimately there just wasn't enough processing power or memory to do it.<br />
<br />
On the flip side, the focus on usability led to very nice improvements in the ground side of things. It (and CC3D) also created a lot of positive publicity as well as a revenue stream for the project.</div>
<div>
<br /></div>
<div>
The first several hundred of these were manufactured by CheBuzz, elafargue and Dankers - so a big thanks to them for taking that risk and getting OP on the map.</div>
<div>
<br />
<h3 style="text-align: left;">
PipXtreme modems (2011)</h3>
</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiWuc6W9J9RzdQpEfdkzw1YhuFcGQhlVIgfL1DtGp0gC6MQqpr9EDP6MyhLynOse8ywymw0D58M0Mx3rFcwZUGdqgzs55uLwAMIAxmdKABaCNnS8buNsHJJAksLEDhHnJyIongF8BnunpY/s1600/IMG_20141025_155750.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiWuc6W9J9RzdQpEfdkzw1YhuFcGQhlVIgfL1DtGp0gC6MQqpr9EDP6MyhLynOse8ywymw0D58M0Mx3rFcwZUGdqgzs55uLwAMIAxmdKABaCNnS8buNsHJJAksLEDhHnJyIongF8BnunpY/s1600/IMG_20141025_155750.jpg" height="285" width="320" /></a></div>
<div>
These modems were designed by Pip, a really talented electrical engineer who was in the project and helped out a ton with lots of designs. They were much more convenient to bind and configure than my experience with other modems and were quite useful for debugging and testing. They also allowed us to build in awareness of UAVTalk into the modem.</div>
<div>
<br /></div>
<div>
Here is Edouard Lafargue testing his out (he also made a nice case for the modem): https://vimeo.com/17200010</div>
<h3 style="text-align: left;">
CC3D</h3>
<div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjM6MhaDrQcXguXhhKEhpobt5Ju5wVsQibvS5tnnJIK39dqd0lNRmzDWqWzjGT2wEH3-O6RRzJM4z_ICCB9hfkOoBFq5n2Br5lYntO9tjgK7GIbA_UOca9u2H-05_b03dLfoF_Sivp9RrU/s1600/IMG_20141025_162117.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjM6MhaDrQcXguXhhKEhpobt5Ju5wVsQibvS5tnnJIK39dqd0lNRmzDWqWzjGT2wEH3-O6RRzJM4z_ICCB9hfkOoBFq5n2Br5lYntO9tjgK7GIbA_UOca9u2H-05_b03dLfoF_Sivp9RrU/s1600/IMG_20141025_162117.jpg" height="176" width="400" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
This was an update to the sensors for CopterControl. Above you can see two versions - one using L3GD20 gyros and BMA180 and the other using the MPU6000. That was interesting because I got to learn about Allan variance testing to compare the sensor drifts. Ultimately we went with the MPU6000.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
One thing that really helped jump start this board was sending out samples to some pretty good pilots in the community, as well as a few developers. Here are 15 boards I soldered by hand:</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEicg7AsaS_dfY7YacsPHCwXwoyMFE_96omKVV-Ad93xDGABKOE6PtSE9Nu-LALm1RrTgweffeK7bInuPmeJzEqV43-dY1doiQphISIQGEjGoYVGbOUG4r-dPT1zzPizrIrYg-5hcW5TOlU/s1600/cc3d.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEicg7AsaS_dfY7YacsPHCwXwoyMFE_96omKVV-Ad93xDGABKOE6PtSE9Nu-LALm1RrTgweffeK7bInuPmeJzEqV43-dY1doiQphISIQGEjGoYVGbOUG4r-dPT1zzPizrIrYg-5hcW5TOlU/s1600/cc3d.jpg" height="186" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
Not a lot of fun to make, but everyone was really happy with how it flew. I believe one of these went to juz, and we all know how worthwhile those videos ended up being.<br />
<br />
This board really sold well and it was hard to keep up with demand. In fact the first few batches were quite terrifying. The yields were extremely low, with sensors frequently failing. Over the batches of the CopterControl the yield had been steadily decreasing but never quite so bad (which also confused us since the first batch from CheBuzz was >95%). It turned out that the assembly house was using ultrasonic cleaning which the MEMS sensors <b>do not</b> like. David had to heroically replace <b>hundreds</b> of MPU6000 by hand, which was weeks of work and cost quite a bit as Invensense would not replace them all.<br />
<br />
Again, in retrospect some decisions could have been done differently. One of the biggest criticisms of CC3D was that it was always unavailable. Once the design was released CC-BY-SA (due to pressure from the developers that things were meant to be open source and the design was years old), tons of manufacturers started making it. Lots of them contributed back to OP and thus provided a risk-free and stress-free revenue stream instead. Trying to corner all the profit ultimately created a lot of stress (and thus pressure on the developers and a lot of tension in the project).<br />
<br />
<h3 style="text-align: left;">
<a href="http://buildandcrash.blogspot.com/2011/11/esc-development.html">ESCs (end of 2011)</a></h3>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh9vcDGN4oB1LtNEo81n7uIfL1z6t_m4PnGiDO-w15Fs5XLI6zEfKLht5QZZIRvJMjf3ZpMYPDo98xoETdqUarIGMoSyPwwbjBRZuL3Wcx88OfSoFCi8EpCxCVuMtm_9bpWUXqlSQIHxjc/s1600/IMG_20141025_161706.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh9vcDGN4oB1LtNEo81n7uIfL1z6t_m4PnGiDO-w15Fs5XLI6zEfKLht5QZZIRvJMjf3ZpMYPDo98xoETdqUarIGMoSyPwwbjBRZuL3Wcx88OfSoFCi8EpCxCVuMtm_9bpWUXqlSQIHxjc/s1600/IMG_20141025_161706.jpg" height="236" width="320" /></a></div>
<div>
<br /></div>
<div>
Who doesn't want an ESC as big as their flight controller? Believe it or not, I actually flew with those. Back then, there was no simonK firmware and the speed of ESCs was the biggest limitation in flight performance. This was confirmed when I saw our software flying on a mikrokopter with their ESCs and it was just totally locked in. Unfortunately, my experience with those I2C ESCs was a lot of bus lockups and crashes (I would not recommend I2C as a protocol for an ESC to my worst enemy).</div>
<div>
<br /></div>
<div>
Anyway, I wanted to play with ESCs so whipped up that huge board you see above. That was a lot of fun. After some shrinking:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg3FKD2NWXfw_2Kt2a4e5qbErBVXYoguNpUYxTvXiTMyt_ITJ9UUgzYvBZgSf1hWE7MwQaflXU7G-Z4yVC4I129Tv1Xo95DSs-ldwxxbCl2Nj8kfTLUm4NGKVGABxpB5sCJlnZRb4Yn0A0/s1600/IMG_20141025_161830.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg3FKD2NWXfw_2Kt2a4e5qbErBVXYoguNpUYxTvXiTMyt_ITJ9UUgzYvBZgSf1hWE7MwQaflXU7G-Z4yVC4I129Tv1Xo95DSs-ldwxxbCl2Nj8kfTLUm4NGKVGABxpB5sCJlnZRb4Yn0A0/s1600/IMG_20141025_161830.jpg" height="251" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiHo7-AbpZYbuxiLMku8LQ9LmaQck1lgcDZfN0Gk_iZw2IB71mkhLPpeUcu00OLZFYHYRath7PY8NsZMDY22ykGHGnuGSzitgl-182b2IEeRJLlGhb9wwbReyVLGF8PP-e99gvRGv-MN-8/s1600/IMG_20141025_161845.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiHo7-AbpZYbuxiLMku8LQ9LmaQck1lgcDZfN0Gk_iZw2IB71mkhLPpeUcu00OLZFYHYRath7PY8NsZMDY22ykGHGnuGSzitgl-182b2IEeRJLlGhb9wwbReyVLGF8PP-e99gvRGv-MN-8/s1600/IMG_20141025_161845.jpg" height="304" width="320" /></a></div>
<div>
<br /></div>
<div>
I had a board that worked pretty decently. However at the same time dirty cheap flashed ESCs became available so these stopped being useful. I still fly them on a number of my boards though. Another pile of work that was wasted. I wrote a really nice system for switching the PWM lines into an emulated bidirectional USART and digitally configuring them via the GCS and the FC. You could even update the code via the PWM line. *sigh*.<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/32459975" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Thanks to MattL for helping with the final shrinking of the design!<br />
<br /></div>
<div>
See more here: http://buildandcrash.blogspot.com/2011/11/esc-development.html</div>
<h3 style="text-align: left;">
Revolution (end of 2011)</h3>
</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiIz6w6MOwRw2HWEkkrwguwWGv8q35X40XZoK5-2VPxFwi1_B5puR-LrrKwZVX5JjIzMvRTpFtW93xHem7TmNVKnTxulBXEi_sg3hMSxOlAagc4W3xc8i8XIG5QBiGQ5YGNrt6487JQJJ4/s1600/IMG_20141025_161032.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiIz6w6MOwRw2HWEkkrwguwWGv8q35X40XZoK5-2VPxFwi1_B5puR-LrrKwZVX5JjIzMvRTpFtW93xHem7TmNVKnTxulBXEi_sg3hMSxOlAagc4W3xc8i8XIG5QBiGQ5YGNrt6487JQJJ4/s1600/IMG_20141025_161032.jpg" height="217" width="320" /></a></div>
<div>
<br /></div>
<div>
This board was designed by David to get development back on track for more advanced functionality. It had gyros, accels, mag, and baro so was capable of full navigation. It also upgraded to an F4 processor which had more than enough power to handle all these tasks. It was also nice for having tons of connectivity. Unfortunately I don't have any first flight videos, because for some reason we were trying to keep things quiet. Here is a video of the first altitude hold, though.<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/36433767" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Of course, this board also had a number of revisions to try out various sensor combinations. Lots of hand soldering for me *sigh*. If you look closely below you can even see some nice blue wires and bent pins to work around various bugs in the early versions.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4t4umOjmFmxGp9QE2-bTxj381Mkm7vnmTntAbK6lWbbDbJfmrJedqh6x9yZDiybcqbNK1xGkJqsKjOtZz_hdYT5Sur6lcL1bBEBG-RKCkBTFbpU1XrazHvhpu38JM3DfbHdrn3RK_c54/s1600/IMG_20141025_160142.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4t4umOjmFmxGp9QE2-bTxj381Mkm7vnmTntAbK6lWbbDbJfmrJedqh6x9yZDiybcqbNK1xGkJqsKjOtZz_hdYT5Sur6lcL1bBEBG-RKCkBTFbpU1XrazHvhpu38JM3DfbHdrn3RK_c54/s1600/IMG_20141025_160142.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
I'm calling this version the "nope". I got this board in the mail, took one look, and said no way am I populating that, because no one will ever want to fly it. Very big.</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiHws9gRjARTOwYexu5vyfn2KidCO12_ovdWWAvEmFXdXNJh_oyueHqV6TOTGnaGyRR_Wk7j8F_MMAfJ_m-GWWNKW1IjB1g229AsWa7_CqxZBvIyzVcvdlk_828TcheecCO_v8XjXic1bA/s1600/IMG_20141025_195309.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiHws9gRjARTOwYexu5vyfn2KidCO12_ovdWWAvEmFXdXNJh_oyueHqV6TOTGnaGyRR_Wk7j8F_MMAfJ_m-GWWNKW1IjB1g229AsWa7_CqxZBvIyzVcvdlk_828TcheecCO_v8XjXic1bA/s1600/IMG_20141025_195309.jpg" height="223" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
One thing that was super useful was designing a board that could carry an Overo gumstix connected to Revolution via SPI. I'm pretty sure I used this board to capture the data in this video (https://vimeo.com/42015859).</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjyk83Aj9osu2P4FqoBkWWLJoNQX2SUnrEoe3kYUjEGT8HIJQjc-U7Cy_N4iF36nPvWY7v5MxZy3MVXDRaH0JhZOHDEf31JetoKlDook7X_iJYqPsIHakaUQzWyMF0yKjvY9GnOnoFn53k/s1600/IMG_20141025_162514.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjyk83Aj9osu2P4FqoBkWWLJoNQX2SUnrEoe3kYUjEGT8HIJQjc-U7Cy_N4iF36nPvWY7v5MxZy3MVXDRaH0JhZOHDEf31JetoKlDook7X_iJYqPsIHakaUQzWyMF0yKjvY9GnOnoFn53k/s1600/IMG_20141025_162514.jpg" height="320" width="283" /></a></div>
<h3 style="text-align: left;">
OSD</h3>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEghy9XagC4HzSUI3pkRyPO0MDtA0banDzwKGNVkicH_S93K0a5-WRTwahE2nzlh-5n8bF29OlR04grRiMwEOzpNTDnO7biNYrcqDAaEF_NWzYCwe5GDATKD5StI7-y3TOdLTcolTrpLRNU/s1600/IMG_20141025_181911.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEghy9XagC4HzSUI3pkRyPO0MDtA0banDzwKGNVkicH_S93K0a5-WRTwahE2nzlh-5n8bF29OlR04grRiMwEOzpNTDnO7biNYrcqDAaEF_NWzYCwe5GDATKD5StI7-y3TOdLTcolTrpLRNU/s1600/IMG_20141025_181911.jpg" height="286" width="320" /></a></div>
<div>
<br /></div>
<div>
This board was motivated by Sambas who initially breadboarded some driver circuitry. I feel badly that I cannot remember the name of the guy that did the design and layout. The original design didn't work great for black and white so you can see the work I did jury-rigging up a different driving circuit. This worked reasonably (although still had issues drawing to the edges of the screen). Ultimately, this stalled due to lack of time.</div>
<div>
<br /></div>
<div>
This is where the strength of open source is great, though. Two people with Tau Labs have designed new flight controllers that have integrated OSD using this code. </div>
<div>
<br /></div>
<div>
<a href="http://forum.taulabs.org/viewtopic.php?t=154&p=1445">Draco</a><br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" src="//www.youtube.com/embed/KBf34QRr3P8" width="500"></iframe>
</div>
<h3 style="text-align: left;">
<span style="font-weight: normal;">and <a href="http://forum.taulabs.org/viewtopic.php?f=21&t=150">Brain</a></span></h3>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" src="//www.youtube.com/embed/jzZu3k3VTFI" width="500"></iframe>
</div>
<h3 style="text-align: left;">
RevoMini (2012)</h3>
</div>
<div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEheZXSL5V7PZ7KcwaJ-Kjj1ZMmpgq6VwhKmaJZxVw2rr8B6rCo0IWBD7mKsKNiH336IGrlGaHtajO2OZDLXi1RrD7y1ycuwqBESav1cX9LhrGDtEquojp2McifnEZqtBc89hn4xcLItdRs/s1600/IMG_20141025_160813.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEheZXSL5V7PZ7KcwaJ-Kjj1ZMmpgq6VwhKmaJZxVw2rr8B6rCo0IWBD7mKsKNiH336IGrlGaHtajO2OZDLXi1RrD7y1ycuwqBESav1cX9LhrGDtEquojp2McifnEZqtBc89hn4xcLItdRs/s1600/IMG_20141025_160813.jpg" height="255" width="320" /></a></div>
<br />
RevoMini (which became known as Revo) was a stripped down (in terms of connectivity) version of Revolution with an integrated modem designed by David. It was good and bad, too. After spending almost a year working on Revolution it created another serious delay in progress on the flight front to focus on basic hardware bringup. In addition it went a bit too far (IMO) dropping connectivity since I use a digital receiver that left one port which isn't enough for GPS and an auxillary mag, or an OSD, etc. Another one that wasn't fun to solder, especially with all the EMI filters on every port.<br />
<br />
Of course, the obligatory first flight video:<br />
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="283" mozallowfullscreen="" src="//player.vimeo.com/video/48211124" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
I ended up being quite unhappy with the flight performance of Revo (I could never get it tuned as nicely as CC3D). There was ultimately a question of whether the problem was hardware or software (although the same software was used on full Revolution, so that wasn't really a question in my opinion). There was also an issue that Revo wasn't looking like open source hardware and there were a lot of political problems within OP (such as doing a preorder for a board that didn't fly well).<br />
<br />
Ultimately this and a number of other issues led to the majority of the developers being told their opinions don't matter and leaving OpenPilot to create <a href="http://taulabs.org/">Tau Labs</a>.<br />
<br />
It also led to me designing...<br />
<h3 style="text-align: left;">
<a href="http://buildandcrash.blogspot.com/2012/11/assembly-and-first-flight.html">Freedom</a> (end of 2012)</h3>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEikgl-whQUcsnCj9nv0gTW_C7ZN7orhvI7lqY2zg8WGkvMSVQr5U9RZL1aNZVP-YjTAMzB7V5MN3UHVTSACYEIyDKZFEWRVVJEh_zqG_JBevEHAGvBSIrmUS7LD6XbQhlkqRHi5TvRtzUU/s1600/IMG_20141025_164740.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEikgl-whQUcsnCj9nv0gTW_C7ZN7orhvI7lqY2zg8WGkvMSVQr5U9RZL1aNZVP-YjTAMzB7V5MN3UHVTSACYEIyDKZFEWRVVJEh_zqG_JBevEHAGvBSIrmUS7LD6XbQhlkqRHi5TvRtzUU/s1600/IMG_20141025_164740.jpg" height="225" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
This board has an MPU6000, HMC5883, RFM22B radio, nice switching regulator, and F4 processor, not to mention a Gumstix Overo computer running linux on the back. The computer and FC stay in sync with a high speed serial bus. I have mostly used it for collecting high resolution sensor logs from flight for offline analysis and algorithm development. This is extremely useful, because you can replay the sensor data from the same flight through numerous algorithms or the same algorithm with different parameters and compare the performance.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div>
It also resolved the question of tuning since it tunes up and flies very well and didn't have the same sensor noise as RevoMini.</div>
<div>
<br /></div>
<div>
Ultimately most end users don't want a linux computer on their flight controller so it didn't make much sense to make lots of these. There are still some issues with not using the ports optimally, and I'm always meaning to clean it up, update the sensors to more modern ones, and make a new revision. There is also something called Aerocore from Gumstix that is similar and I'd like to port the linux code to.It's always a matter of not enough time! I love it though and it is great for development, still. </div>
<div>
<br /></div>
<h3 style="text-align: left;">
<a href="http://buildandcrash.blogspot.com/2013/05/sparky-testing-and-building-no-crashing.html">Sparky</a> (2013)</h3>
<div>
At this point, I knew what I wanted in a flight controller. Reasonable expandability and IO, capable of altitude hold, position hold and return to home, cheap and easy to assemble, and open source. Since there wasn't something like that, I designed one.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjB1i-ibJU67NcjThsZx3RdS7p76Qr4ozkaCkKKjrxgXuryV0Wf7xb5zGFN3OCq2l1ybdNTMhGhDJ9AiFDbfdHLHP7NrR3-4U1ZvBK_6YqNnuoc4h-xoSZBuoeKlcEAdcfs0-6hrGDSUdA/s1600/IMG_20141025_160849.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjB1i-ibJU67NcjThsZx3RdS7p76Qr4ozkaCkKKjrxgXuryV0Wf7xb5zGFN3OCq2l1ybdNTMhGhDJ9AiFDbfdHLHP7NrR3-4U1ZvBK_6YqNnuoc4h-xoSZBuoeKlcEAdcfs0-6hrGDSUdA/s1600/IMG_20141025_160849.jpg" height="236" width="320" /></a></div>
<div>
<br /></div>
<div>
I'm quite proud of Sparky. It flies <i>extremely</i> well. It switched to the MPU9150 which integrates the mag into the accels and gyros and keeps the sensors all together. It uses an MS5611 pressure sensor, which is quite nice. It has enough resources to be quite capable while keeping it fairly affordable (the Chinese make it for < 40$), all the components are on the top so it is not too bad for assembling yourself (the MPU9150 is a bit nasty). I find the receiver port extremely useful compared to tying up one of the serial ports for my Spektrum receivers.<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="375" mozallowfullscreen="" src="//player.vimeo.com/video/63619336" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<br /></div>
<div>
I get some grief about the shape ;-). It was designed for my tastes, so that is fine. Typically I use a three point mounting and have never had an issue. I figured if I don't need to use board space, why keep it? I did make an earlier version that kept the thing as small as I could get it (without using the back). This <b>was</b> a pain to mount since none of my frames had that spacing. Ultimately adding the tab made it compatible with other frames while able to have the tab cut off and fit in smaller spaces (since the back is flat you can mount it by taping).</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGRd_0APh_VVh650lklk6W7EP5P1ki6MJRu0xGro46Eo2An31-7sM37wp0wau-T0mGngQGoQSVWwGa9125x7t7zzBEbgPlR6JJQ2oIWrRyI3k0MtjMNlC7-qbwYGZ9I_vhqoFQTd6cO-0/s1600/IMG_20141025_181812.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGRd_0APh_VVh650lklk6W7EP5P1ki6MJRu0xGro46Eo2An31-7sM37wp0wau-T0mGngQGoQSVWwGa9125x7t7zzBEbgPlR6JJQ2oIWrRyI3k0MtjMNlC7-qbwYGZ9I_vhqoFQTd6cO-0/s1600/IMG_20141025_181812.jpg" height="242" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Here is version 1.1 which updated a few of the passive on the sensors to be better in spec and also switched to a three pin header for the receiver so standard cables can be used. I still flip-flop on the 3 versus 4 pin distinction.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiajfvFgk8qCN8_NdjJDjV7JK3-ML5xy5XsurKOi3MGkNX5LXHX9909JBmE3W_2Fb2RpzOfEK3VEf7RQt4CqC2capNscEMDllu4e894390ufm-WnEKdtDmmdGsoVu3emM7oJ9YHbq-tzMA/s1600/IMG_20141025_164318.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiajfvFgk8qCN8_NdjJDjV7JK3-ML5xy5XsurKOi3MGkNX5LXHX9909JBmE3W_2Fb2RpzOfEK3VEf7RQt4CqC2capNscEMDllu4e894390ufm-WnEKdtDmmdGsoVu3emM7oJ9YHbq-tzMA/s1600/IMG_20141025_164318.jpg" height="288" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
And they same imitation is the best form of flattery, so here are some boards made by Dragon Circuits. The design is CC-BY-SA so that is totally legal and ethical. I do not receive anything from them for the boards, but that is fine. They make it available more cheaply to more people and that is good.</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh4Nr1QK6amTVywkdF0z47F4YOEMDn95y86CnrwcSOomhAd4pwWFv1035PdysaEXGa_gLm7uPBH8v27XIIUiyzmxh5KZp3whceUVqhpr7ljvRPMHX7-MRTmunAQXAFF9gsGls9AP1RLM7M/s1600/IMG_20141025_160837.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh4Nr1QK6amTVywkdF0z47F4YOEMDn95y86CnrwcSOomhAd4pwWFv1035PdysaEXGa_gLm7uPBH8v27XIIUiyzmxh5KZp3whceUVqhpr7ljvRPMHX7-MRTmunAQXAFF9gsGls9AP1RLM7M/s1600/IMG_20141025_160837.jpg" height="235" width="320" /></a></div>
<div>
<br />
<h3 style="text-align: left;">
<a href="http://buildandcrash.blogspot.com/2013/05/brushless-gimbal-driver-add-on-for.html">Sparky Brushless Gimbal Controller</a></h3>
</div>
<div>
At the same time as Sparky, I also designed a "shield" that could be soldered to the back and converted the 6 PWM outputs to 2 brushless gimbal outputs.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjmv2blHLPNEaMWasbKLjAT3SRUHuG80f0_ccA2-9hchIFoqGVCXGFgg47eifYoZFAvahsHPuB7C0_aK3EYNGrzDsXZvJ0QPvmHQDOJO2d7keVte8ZwLbkYDFPU6WueHQV-ICtArRDjhMc/s1600/IMG_20141025_161217.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjmv2blHLPNEaMWasbKLjAT3SRUHuG80f0_ccA2-9hchIFoqGVCXGFgg47eifYoZFAvahsHPuB7C0_aK3EYNGrzDsXZvJ0QPvmHQDOJO2d7keVte8ZwLbkYDFPU6WueHQV-ICtArRDjhMc/s1600/IMG_20141025_161217.jpg" height="228" width="320" /></a></div>
<div>
<br /></div>
<div>
This was a pretty different project and I won't write it up too much here. I was happy with the performance.<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/66987484" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Having the ability to talk (via CAN) between the BGC and FC is quite useful and can allow things like point of interest tracking:<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/91046135" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<br />
The shield made it easy for me to test this out without designing a new board. However, ultimately having the whole FC+driver on the gimbal isn't the optimal configuration so I redesigned it with a more 'traditional' configuration.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhKx66awYRgpQPy_tr60uck9QY09r2v6QZfC0SILjT8mEWTmJkixJqEpCqivqB3y8BCBZU50llWqvkS3VycfpXojyVYWt3Pk6xjBBMmNsM5zgAF6gkd-QpGTl2IVQpurUT8raozZpsXqJc/s1600/IMG_20141025_161056.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhKx66awYRgpQPy_tr60uck9QY09r2v6QZfC0SILjT8mEWTmJkixJqEpCqivqB3y8BCBZU50llWqvkS3VycfpXojyVYWt3Pk6xjBBMmNsM5zgAF6gkd-QpGTl2IVQpurUT8raozZpsXqJc/s1600/IMG_20141025_161056.jpg" height="290" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="clear: both; text-align: left;">
<a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">TauLink</a> (2014)</h3>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiBTA3No4ItooH6UxGT_SwBa1NbUvL92ErGHJMHN0dk0ycHSoDTMit-ZoH6W_Nyzr6ck8k_w75oO4KDyDf7Q198f7KmE2O08-5VnT4AdWHIA_nSm7EgKbP_6xiHlqYEZyRLbS9JJ22GCYY/s1600/IMG_20141025_160952.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiBTA3No4ItooH6UxGT_SwBa1NbUvL92ErGHJMHN0dk0ycHSoDTMit-ZoH6W_Nyzr6ck8k_w75oO4KDyDf7Q198f7KmE2O08-5VnT4AdWHIA_nSm7EgKbP_6xiHlqYEZyRLbS9JJ22GCYY/s1600/IMG_20141025_160952.jpg" height="314" width="320" /></a></div>
<div>
<br /></div>
<div>
I wanted an radio link I could use to talk to Freedom and Sparky2 that stayed code compatible with the original PipX. This is the result, it's fairly straightforward - just a few serial ports and the RFM22b modem on the bottom.</div>
<div>
<br /></div>
<div>
Since I mostly use this on the ground side plugged into either my laptop or an OTG adapter for my phone, I realized the form of a thumb drive is actually a bit more effective for my purposes.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_zD_BuXBDNlRdhA1_BQtRkvia9-MoYGEXYVtckosKdfG9A2nf0QwV7hdvpMay1oDbjvmYC1Pv8oUQoivUzkGKpm9DtP44HgY_BmFMJOaBzn1amL99Oe0vLF04YeK-sxZUWlWSSyRJGb4/s1600/IMG_20141025_161016.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_zD_BuXBDNlRdhA1_BQtRkvia9-MoYGEXYVtckosKdfG9A2nf0QwV7hdvpMay1oDbjvmYC1Pv8oUQoivUzkGKpm9DtP44HgY_BmFMJOaBzn1amL99Oe0vLF04YeK-sxZUWlWSSyRJGb4/s1600/IMG_20141025_161016.jpg" height="320" width="315" /></a></div>
<div>
<br /></div>
f
It can also be used on the flight side with Sparky, in which case I'd probably leave the USB connector off ;-).<br />
<br />
<h3 style="text-align: left;">
<a href="http://buildandcrash.blogspot.com/2014/08/sparky-20-and-taulink.html">Sparky 2</a> (2014)</h3>
</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgSNh0Xjinl81tob63gOMhIH666TxhHhYdVFZlDSJgElHiYTRI_lTnlnxz_Blg1qMOzXEv8_ASIXPLjUBKHuBl2UPf7WF4MW6Lz_lWA8dGdNcuV311k9BQOPV7tBPD0AYqIkel_c6I0SKY/s1600/IMG_20141025_160908.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgSNh0Xjinl81tob63gOMhIH666TxhHhYdVFZlDSJgElHiYTRI_lTnlnxz_Blg1qMOzXEv8_ASIXPLjUBKHuBl2UPf7WF4MW6Lz_lWA8dGdNcuV311k9BQOPV7tBPD0AYqIkel_c6I0SKY/s1600/IMG_20141025_160908.jpg" height="310" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Finally Sparky2. This is designed more with navigation and advanced features compared to Sparky1. It switches to an MPU9250 which has a tiny bit worse noise performance (although so far below the motor noise it is irrelevant) but has the benefit of being an SPI sensor and not taking up as much CPU usage. It adds an RFM22b module for telemetry which is key for serious navigation (and honestly advised for even PH). It also adds an additional auxillary I2C port for communicating with a mag, which is useful for having more accurate reading. It adds flash for storing short logs or storing waypoints and picoC code. There is a DAC outputs for an audio downlink with FPV, although I haven't had the chance to play with that yet.</div>
<div>
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/104670658" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<h2 style="text-align: left;">
Summary</h2>
<div style="text-align: left;">
That is a lot of hardware. Tons of people were involved in all aspects - hardware design, soldering prototypes, writing code and testing. Thanks to everyone that has been involved and made it a very fun and interesting four years. I won't even pretend this is a complete list but special thanks to PT Dreamer, Edouard Lafargue, stac, pip, kubrak, CheBuzz, Vasillis, Corvus, Bwebbn, Angus, and David for their tireless work and contributes to keep this going in various forms.</div>
<div style="text-align: left;">
<br /></div>
<div style="text-align: left;">
This post also focused heavily on hardware that I had a hand in designing or getting flying. In fact I think all the flight controllers listed above were first flown by me ;-). Open Source is very powerful in the fact the Tau Labs system keeps growing and supporting tons of other targets not mentioned here. This includes:</div>
<div style="text-align: left;">
</div>
<ul style="text-align: left;">
<li>Quanton</li>
<li>FlyingF3</li>
<li>FlyingF4</li>
<li>Gemini (Colibri flight controller)</li>
<li>Brain</li>
<li>Draco</li>
</ul>
<div>
and probably others I don't even know about yet!</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com10tag:blogger.com,1999:blog-1759046512792102553.post-64426934848595620692014-08-29T14:01:00.000-07:002015-05-14T19:54:47.534-07:00Sparky 2.0 and TauLink<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<b>Update2: Sparky2 is available here <a href="http://www.hobbiesfly.com/taulabs-sparky2-0.html">http://www.hobbiesfly.com/taulabs-sparky2-0.html</a></b><br />
<b><br /></b>
I love <a href="http://buildandcrash.blogspot.com/2013/05/sparky-testing-and-building-no-crashing.html">Sparky</a>. It's not too surprising, since I designed it to be everything I want in a flight controller. Simple, easy to solder, small, extremely capable, reasonably expandable.<br />
<br />
I also really like <a href="http://buildandcrash.blogspot.com/2012/11/assembly-and-first-flight.html">Freedom</a>, the more powerful cousin. The overo allows logging all the data, which has been hugely powerful. It has more connectivity which is great for having an external mag, spektrum, gps and OSD. The integrated radio is very convenient for connecting to Android.
The obvious thing to do was try and fuse them together and get the best of both worlds.<br />
<br />
My main goal with this project is something that is really easy and effective for doing POI tracking, follow me, as well as still just flying really well and being great for navigation.<br />
<br />
I present:<br />
<h3 style="text-align: left;">
Sparky 2.0 </h3>
<div style="text-align: left;">
<br /></div>
<div dir="ltr" style="text-align: left;" trbidi="on">
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi1YrKPveaZ5SkAuyPCYy3cWiFjNnsJVVqI-3LGTBpd6rtL0F3BS9qKyy7-msY8YbxwUg3IMmH11ES-bZJIv8HoYK50_HGa8JbSh8G8Y_Ajp7TxGMakJaIPdhMQ9IlUluc4bYreZUe7qGs/s1600/Screen+Shot+2014-08-28+at+12.06.57+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="289" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi1YrKPveaZ5SkAuyPCYy3cWiFjNnsJVVqI-3LGTBpd6rtL0F3BS9qKyy7-msY8YbxwUg3IMmH11ES-bZJIv8HoYK50_HGa8JbSh8G8Y_Ajp7TxGMakJaIPdhMQ9IlUluc4bYreZUe7qGs/s1600/Screen+Shot+2014-08-28+at+12.06.57+PM.png" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjoYhdoHZQCmw6j8lt5mO6N2xlALuM-x_htnBs3OarDOTYmpScgnDZsJyzb-LM0inle5aPUb1mFZz9cWgH5b5jCjW1Qnf8VIeIwwPYgOoyY7PgR8PZoheXoev56lF6A9OV3-30wCvxeWTs/s1600/IMG_20140828_021949.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjoYhdoHZQCmw6j8lt5mO6N2xlALuM-x_htnBs3OarDOTYmpScgnDZsJyzb-LM0inle5aPUb1mFZz9cWgH5b5jCjW1Qnf8VIeIwwPYgOoyY7PgR8PZoheXoev56lF6A9OV3-30wCvxeWTs/s1600/IMG_20140828_021949.jpg" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjOpmGNK2le1D-LXOnQtBFI4qQaG4A3gS6fIUobMyT1HkWKLB1PJeP9XdEJMIbhSLomxNvM3FnvELjalO04jzd9SzsYjuMFSRwJYBLpBNMSBpcarBll3hS36kH8xBpzu0k1zJPqIlSpUI4/s1600/IMG_20140828_105151.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjOpmGNK2le1D-LXOnQtBFI4qQaG4A3gS6fIUobMyT1HkWKLB1PJeP9XdEJMIbhSLomxNvM3FnvELjalO04jzd9SzsYjuMFSRwJYBLpBNMSBpcarBll3hS36kH8xBpzu0k1zJPqIlSpUI4/s1600/IMG_20140828_105151.jpg" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjuduVVyOC43TJl6a7yLxCmJsXk6OJ-j_v0Q3bOVAAfJMG7iDMvWAx-bHzzQsX56WcTPu0xUfhb4x2JxYEZbPvhOjGQU5050LJRtTCStBR1EveyCnjd4ttaDDsqnhSbdxLKfsouJvBOFgM/s1600/IMG_20140828_105206.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjuduVVyOC43TJl6a7yLxCmJsXk6OJ-j_v0Q3bOVAAfJMG7iDMvWAx-bHzzQsX56WcTPu0xUfhb4x2JxYEZbPvhOjGQU5050LJRtTCStBR1EveyCnjd4ttaDDsqnhSbdxLKfsouJvBOFgM/s1600/IMG_20140828_105206.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="text-align: left;">
Features</h3>
<ul style="text-align: left;">
<li>Runs <b>Tau Labs</b> (of course ;-). Same great flight performance you've come to expect and standard features.</li>
<li><b>Open source hardware! </b>(also of course) </li>
<li><b>More powerful processor</b>. Uses an STM32F4 running at 168 Mhz with increased memory and flash. This is useful for storing and flying longer waypoint sequences and running more complicated code like picoC scripting.</li>
<li><b>More connectivity</b>. (RCVR, Flexi, Main, I2C Aux). This is really useful if you want to have an external mag, gps, and spektrum receiver or other things like OSD.</li>
<li><b>Flash chip</b> which can be used to store flight plans, picoC code, or logging</li>
<li><b>RFM22b radio</b> can be used for telemetry or with openlrng (not implemented yet). The receiver antenna uses the same U.Fl. connector that Freedom has. I really like this because it is very small and you can easily an SMA break out cable or a whip antenna. It also has just the right amount of tension - strong enough to hold together in flight but in a crash it will disconnect and not damage the board. There is a small hole at the front to provide strain release for a whip antenna that you can just pass through and solder straight to the RFM22b for minimal configurations.</li>
<ul>
<li><b>OpenLRS support</b> <a href="https://vimeo.com/124850842">directly control from your OpenLRSng radio </a>if you don't want a TauLink </li>
</ul>
<li><b>Four buffered outputs</b> to drive either LEDs (indicate flight status) or brushed motors. I'm really excited to have different colored LED strips turn on to indicate the direction it is facing relative to home.</li>
<li><b>DAC output</b> for VTX audio telemetry. I'd like to be able to some prerecorded audio sounds so the headphones can provide useful information for FPV.</li>
<li><b>Dual analog input</b> for voltage and current monitoring. The DAC output can also be used as an analog input.</li>
<li><b>CAN Bus</b> which is very useful for talking to external devices like the <a href="http://buildandcrash.blogspot.com/2014/08/sparky-brushless-gimbal-controller.html">brushless gimbal</a> to coordinate <a href="https://vimeo.com/91046135">POI tracking</a> or control the gimbal pitch from transmitter. Also CAN enabled ESCs are coming out which will allow serious improvements in flight quality.</li>
<li><b>Full sensor suite</b> of course. MS5611 baro and MPU-9250 combined gyro/accel/mag. I was really conflicted on switching from the MPU-9150 to the MPU-9250. However, being able to utilize an SPI bus which is much better handled on the processor side made it worthwhile.</li>
<li><b>Optional single sided assembly</b> - the necessary things to fly are all on the top of the board. The bottom has the CAN bus connector, RFM22b, antenna, external LED drivers. So if you just want a more powerful flight controller with more memory and CPU over Sparky it's still single sided.</li>
</ul>
<h3 style="text-align: left;">
Ground modem - TauLink</h3>
<div>
I also needed a ground side modem. This uses the same RFM22b module used on openlsrg as well as on the flight controller and uses an STM32F1. It was inspired by the PipXtreme (which also inspired the OPLink) done by Pip when we were with OP a few years ago, but is a bit smaller and easier to assemble. It's running code written by Pip, Brian Webb and myself. </div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2bSwNL5827iLmJIqJAzbmhuchuri22te8N9KA5gW8rcLbkfM0JCN3Z2Y7ADZhSnwn2RwySXB-9loDNOFMMZoNAZRKzdr81FrN5i5h0-vbVZ6PxiUBFAEoLRPluZf7hI4Lyf95_ozl7fc/s1600/Screen+Shot+2014-08-28+at+12.15.22+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="310" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2bSwNL5827iLmJIqJAzbmhuchuri22te8N9KA5gW8rcLbkfM0JCN3Z2Y7ADZhSnwn2RwySXB-9loDNOFMMZoNAZRKzdr81FrN5i5h0-vbVZ6PxiUBFAEoLRPluZf7hI4Lyf95_ozl7fc/s1600/Screen+Shot+2014-08-28+at+12.15.22+PM.png" width="320" /></a></div>
<div>
<br /></div>
<div>
<br /></div>
<div>
The modem has a standard SMA connector so can accept a wide selection of 433 Mhz antennas. It uses micro USB and can be powered by a phone or tablet and works with the <a href="https://play.google.com/store/apps/details?id=org.taulabs.androidgcs&hl=en">Tau Labs Android GCS</a>. There is also a port that can serve as a receiver port for relaying signals from a transmitter or taking in PPM for a transmitter module. Finally, there is a serial port for connecting to a GPS. This is important for any tracking applications like POI mode since the accuracy of the phone GPS is not sufficient in my experience.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgfxZS6X7yUJWQJD7NCDPyTMhzJ307epVnsSpT2w0KTj4WISgsIUvebfpkgAqVG4ottg0YDU76_26fpv_BGputXz8gdUxkJvZu4nHa3rFv0A0StA6c0SH_m4SUL308-TqCMBZa6xFZ_KzQ/s1600/IMG_20140828_105118.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgfxZS6X7yUJWQJD7NCDPyTMhzJ307epVnsSpT2w0KTj4WISgsIUvebfpkgAqVG4ottg0YDU76_26fpv_BGputXz8gdUxkJvZu4nHa3rFv0A0StA6c0SH_m4SUL308-TqCMBZa6xFZ_KzQ/s1600/IMG_20140828_105118.jpg" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgPJpaeeCNPhsHDqitr2AX4H-n8392Z1X5jAfedXUZuvuwVWMcvKOgtTXHkJ6ZVB9z5-7egm3jaeC0PDCS6XDVLv4VCSbir3YJXL0k83Wk-mVVXiFq7LleGCDp2YzgNW02wbHcRFTYncUE/s1600/IMG_20140828_105124.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgPJpaeeCNPhsHDqitr2AX4H-n8392Z1X5jAfedXUZuvuwVWMcvKOgtTXHkJ6ZVB9z5-7egm3jaeC0PDCS6XDVLv4VCSbir3YJXL0k83Wk-mVVXiFq7LleGCDp2YzgNW02wbHcRFTYncUE/s1600/IMG_20140828_105124.jpg" width="320" /></a></div>
<div>
<br /></div>
<div>
<br /></div>
<div>
I also want to break out a few pins to a housing with buttons so the modem can be used to relay a few simple commands like "land" or "follow".</div>
<div>
<br /></div>
<div>
And a quick little case to make it easier to stick to things.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEikzrVS5mr3EBhJkt7xoKfj-_XhY7KyK3xaJS71LnIzuAkj9PTQldBcov0tKUS8Uwh4JUXnuOw3-TkUD6kgGvN1qusa5TQ6psmYGX4v_qGn87j9plV0CMijDjcdOFzr1Gusj2XtgaFWOqY/s1600/Screen+Shot+2014-08-28+at+4.55.05+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="177" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEikzrVS5mr3EBhJkt7xoKfj-_XhY7KyK3xaJS71LnIzuAkj9PTQldBcov0tKUS8Uwh4JUXnuOw3-TkUD6kgGvN1qusa5TQ6psmYGX4v_qGn87j9plV0CMijDjcdOFzr1Gusj2XtgaFWOqY/s1600/Screen+Shot+2014-08-28+at+4.55.05+PM.png" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg0k586VnS-sCZRzvkxS-vmxm7m6UBFRG3w-13EU4GiLcBZsy5DOst0FX2raUiwrPTLtrDlm2OdNf6CxojcdR_PMESHblS5cBXkUxkuDNdwvxVnu-jOVTAdsfTv8EedZjlMV2nKb8F-4SA/s1600/IMG_20140829_073839.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg0k586VnS-sCZRzvkxS-vmxm7m6UBFRG3w-13EU4GiLcBZsy5DOst0FX2raUiwrPTLtrDlm2OdNf6CxojcdR_PMESHblS5cBXkUxkuDNdwvxVnu-jOVTAdsfTv8EedZjlMV2nKb8F-4SA/s1600/IMG_20140829_073839.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
<br /></div>
<h3 style="text-align: left;">
GPS</h3>
<div>
I picked up <a href="http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash-/181465343124">this super cheap Ublox 8 GPS</a> that ReadError recommended on IRC. Conveniently, Sparkfun have also started selling the <a href="https://www.sparkfun.com/products/10359">JST-SH cables</a> needed to connect it. So far the performance looks really quite good, although I haven't flight tested it yet. Our software picked it up right away and autoconfigured it, which was nice.</div>
<div>
<br /></div>
<div>
Unfortunately it didn't have any mounting holes, so I quickly designed a case in OpenSCAD that uses the standard 30.5 spaced holes:</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhlxeb-eYWOYnJp8GbFU-UFqXxwQaP0msK0-dIwdrH8HBU3T76i_PGAKgzwnht2pDpa1r9WlypbEA36abx0OXzwsjqN_yIFsuSaZliFquWMwPX9IF011Ts5B_cPlbkZvTHIRiCzMaYsPYE/s1600/Screen+Shot+2014-08-28+at+12.46.39+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="152" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhlxeb-eYWOYnJp8GbFU-UFqXxwQaP0msK0-dIwdrH8HBU3T76i_PGAKgzwnht2pDpa1r9WlypbEA36abx0OXzwsjqN_yIFsuSaZliFquWMwPX9IF011Ts5B_cPlbkZvTHIRiCzMaYsPYE/s1600/Screen+Shot+2014-08-28+at+12.46.39+PM.png" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhtPJwh1BDOpOH6_DYX0YJVtjZS1p2WqDQhKzeG7vUKEJLqkxO0IfmO4ipTJ8CP4xZ3tQrK5Iwut0xgjp9FT3s7Od2mbhZXDCNvGld7ZMqUzesnPcnG7GQsT-B2PXUUE6kEz8ed9gwf9Nw/s1600/IMG_20140828_134644.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhtPJwh1BDOpOH6_DYX0YJVtjZS1p2WqDQhKzeG7vUKEJLqkxO0IfmO4ipTJ8CP4xZ3tQrK5Iwut0xgjp9FT3s7Od2mbhZXDCNvGld7ZMqUzesnPcnG7GQsT-B2PXUUE6kEz8ed9gwf9Nw/s1600/IMG_20140828_134644.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGb5-b4K2G16yJf0Vx22lU-WKzbbdGY8umsmFlVBMJ7rEpoBjl8sxTunqA5H6D68kTm0IGxa0hORu5_1q8Jt0xPaeI_5P5wXD8Y6pYbuyw8J-8kLGXIKMe8KXibX656WNVu1whqs3YGtQ/s1600/IMG_20140828_140012.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGb5-b4K2G16yJf0Vx22lU-WKzbbdGY8umsmFlVBMJ7rEpoBjl8sxTunqA5H6D68kTm0IGxa0hORu5_1q8Jt0xPaeI_5P5wXD8Y6pYbuyw8J-8kLGXIKMe8KXibX656WNVu1whqs3YGtQ/s1600/IMG_20140828_140012.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h2 style="text-align: left;">
Flight Testing</h2>
<div>
First test was to put all these pieces together. I'm using a modified UAP-1 frame for this. No particular care taken for wiring or spacing between cables and FC. Let's just see how it does.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhSy_beuxEOHXxVN5K51Z4QoJOnb_vBCvKfa8-i1iLQyp2iNCINwufPAcUysHkDSvdDHfmIJdeMbHrQfSJDkJFdjDVXkQ8nkyLZODaDWpWytbAsji328HoF8nUMF2p6m2RbFWYBSqncNTw/s1600/IMG_20140828_184838.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="240" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhSy_beuxEOHXxVN5K51Z4QoJOnb_vBCvKfa8-i1iLQyp2iNCINwufPAcUysHkDSvdDHfmIJdeMbHrQfSJDkJFdjDVXkQ8nkyLZODaDWpWytbAsji328HoF8nUMF2p6m2RbFWYBSqncNTw/s1600/IMG_20140828_184838.jpg" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
I ran through the standard configuration aspects to make sure position hold would work: performed the six point calibration and leveling, got a rough PID tuning dialed in (haven't merged autotune in this branch yet), enabled the appropriate modules, checked the EKF variances, used complementary/INS mode, set one flight mode position switch to leveling and the other to position hold. Took it outside with my phone connected via the modem. </div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/104718506" webkitallowfullscreen="" width="500"></iframe>
</div>
<div style="text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
This is super convenient and practically necessary for any navigation related things - navigation is too complicated and error prone to risk blind. With this I could verify the GPS lock quality, check on the map that things things look sensible, and get audio alerts of any error conditions (e.g. when the GPS loses a lock, which didn't happen today).</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Position hold mode performed really well for a first try (and pretty much first flight of this board outside). Loiter also worked well, although sometimes it seems like it moves 10-15 degrees different than what I expect. I need to check into this. Still it was comfortably controllable, and in fact at one point someone was walking near me and I shifted it without thinking.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div>
<br /></div>
</div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/104670658" webkitallowfullscreen="" width="500"></iframe><br />
<br />
<div style="text-align: left;">
The graphs showing where the quad is were generated from the android logs and the <a href="http://buildandcrash.blogspot.com/2014/03/logging-and-python-parsing.html">python parsing code</a>.<br />
<br />
<h3 style="text-align: left;">
Radio Control via RFM22B (TauLink)</h3>
<div>
<br /></div>
</div>
</div>
<div style="text-align: center;">
<br /></div>
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="https://player.vimeo.com/video/127703051" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<h3 style="text-align: left;">
</h3>
<div style="text-align: left;">
I got out my old transmitter designed to hold a tablet that was made by Kendall and JoeCNC to play with transmitting the PPM stream via the RFM22B module (directly from TauLink to Sparky2 without another transmitter). It worked pretty well and android was connected and giving me updates.</div>
<div style="text-align: left;">
I also tested altitude hold for Sparky2. Worked well first try.</div>
<div style="text-align: left;">
Range testing still to do, although of course the first thing I did was verify that turning the transmitter off put the flight controller into failsafe mode. This actually replicates something I did over a year ago with RevoMini and PipXtreme: vimeo.com/51659303 . Of course, it is nice to do it with Open Hardware.</div>
<div style="text-align: left;">
<br />
Thanks to Brian Webb specifically for writing the PPM transmission code with OpenPilot.</div>
<div style="text-align: left;">
<br />
<h3 style="text-align: left;">
picoC scripting</h3>
<div>
A really awesome feature that was implemented for erniefti is the ability to load custom scripts into the flight controller. This makes it possible for people to pass around small pieces of functionality and easily run it without a custom firmware. He also added an awesome UI for loading this code and testing it recently. </div>
<div>
<br /></div>
<div>
This seemed like a good thing to learn for driving the external LEDs that Sparky2 can run. I decided to write a little code that takes the heading and turns on the LEDs facing northing, giving me an easy external indication of the compass. Here is a video of how easy it is to upload this code and make it run when you start up the flight controller.</div>
<div>
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/105504442" webkitallowfullscreen="" width="500"></iframe></div>
<h3 style="text-align: left;">
Future directions</h3>
<div style="text-align: left;">
Now the hardware is working, there are a few things to implement:</div>
<div>
<ol style="text-align: left;">
<li>LED outputs based on flight. This will probably use picoC to make it easy to change on the fly. I'm envisioning something where the color indicates the heading relative to home and brightness the distance.</li>
<li>Audio alerts. Again, I envision having some prerecorded sounds stored in flash that it transmits over the VTX audio channel and you can hear on the headphones. Low RSSI, low battery, GPS satellites, distance from home every X m, etc. Also possibly just simple beeps encoding health.</li>
</ol>
<div>
More important is the cool things this will enable. Relaying the accurate GPS position of the pilot via TauLink and then having a chase mode. We already have follow me for the tablet (have for a year or two now), but for higher speed stuff a better control scheme that accounts for the target velocity should help.</div>
</div>
<div>
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/63529694" webkitallowfullscreen="" width="500"></iframe> <br />
<br />
<div style="text-align: left;">
If you are interested in testing this board and previously got a Sparky v1 from me, then send me an email.</div>
</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com275tag:blogger.com,1999:blog-1759046512792102553.post-10640703842734269032014-08-27T19:37:00.003-07:002014-11-06T10:04:42.374-08:00Sparky brushless gimbal controller - version 2<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<b>Update: if you want a SparkyBGC please email me (my username at gmail.com) or drop a comment here</b><br />
<br />
I made an add on board for <a href="http://buildandcrash.blogspot.com/2013/05/sparky-brushless-gimbal-controller.html">Sparky last year that added brushless gimbal drivers</a> and found it worked quite well:<br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/66987484" webkitallowfullscreen="" width="500"></iframe>
</div>
<br />
However, because the sensors were all on the main controller board that was a lot to mount on the gimbal. Weight wise, it wasn't a problem. For tuning the gimbal though, having all the cables running to the moving part was a pain. So I redesigned it with a main board with our standard mounting holes and a satellite board with an MPU-9150 to provide the sensing (and be useful as an external mag for navigation).<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhE1fGSqlJIMlAwZTIKfd8UraKlf3EA9w-sEygk-zCtsMAJNbnE0NunKxUUOtglYFwdFm_wk2Rz74TZZ52CkkLJeMwlLKuV_bKoVr8aIRUdfW1yTvlYlpd6n0LGzAxMeOyZNPHVJYeD9Ys/s1600/Screen+Shot+2014-08-11+at+11.34.48+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhE1fGSqlJIMlAwZTIKfd8UraKlf3EA9w-sEygk-zCtsMAJNbnE0NunKxUUOtglYFwdFm_wk2Rz74TZZ52CkkLJeMwlLKuV_bKoVr8aIRUdfW1yTvlYlpd6n0LGzAxMeOyZNPHVJYeD9Ys/s1600/Screen+Shot+2014-08-11+at+11.34.48+AM.png" height="241" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjdNLUX5qlLjM6zg8lOvIi8ccP-bop147HHQzCIav4bogAbfxmLcR-6hJNVJcdRzyrR0JTM21kO0z0pVjcaBvaJFcNRQFMqmo0jflMXNv-7ua9f3KDjztPeBZtyKX30s43xauGHD-HI1UU/s1600/Screen+Shot+2014-08-27+at+9.30.36+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjdNLUX5qlLjM6zg8lOvIi8ccP-bop147HHQzCIav4bogAbfxmLcR-6hJNVJcdRzyrR0JTM21kO0z0pVjcaBvaJFcNRQFMqmo0jflMXNv-7ua9f3KDjztPeBZtyKX30s43xauGHD-HI1UU/s1600/Screen+Shot+2014-08-27+at+9.30.36+PM.png" height="231" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiMyXFKvv1NK51O0bDwAXbo2RTShvVQJFXNRLDagAlFrr0Cz-J4pNfo4S6de_dn9Wz1P0VKqIOCPMMMUYhXsM2J1EzPYu-Qyz1DvD9bReU0tyOUEsZHik1YX2sm31vr0wzNN7xlKS9VFI0/s1600/Screen+Shot+2014-08-27+at+9.31.00+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiMyXFKvv1NK51O0bDwAXbo2RTShvVQJFXNRLDagAlFrr0Cz-J4pNfo4S6de_dn9Wz1P0VKqIOCPMMMUYhXsM2J1EzPYu-Qyz1DvD9bReU0tyOUEsZHik1YX2sm31vr0wzNN7xlKS9VFI0/s1600/Screen+Shot+2014-08-27+at+9.31.00+PM.png" height="320" width="255" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<br />
<h3 style="text-align: left;">
Assembly</h3>
And got the boards back. The sensor board is designed to break off to make it easier to populate the two of them together.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEghMfRb1A-HTlGiPZddE1ChmmVsA36HuyJ1Re3YwmGlZV1qCUPeIjCAF8bSRPR4NQ7TUDRb-ntTxWhXeLH1F_UvJBFJvYrvnwbbv2h3uVW6fbU_A4WUq25Yo23KSWESq96zLWoyzPAPV-E/s1600/IMG_20140826_161029.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEghMfRb1A-HTlGiPZddE1ChmmVsA36HuyJ1Re3YwmGlZV1qCUPeIjCAF8bSRPR4NQ7TUDRb-ntTxWhXeLH1F_UvJBFJvYrvnwbbv2h3uVW6fbU_A4WUq25Yo23KSWESq96zLWoyzPAPV-E/s1600/IMG_20140826_161029.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
And some of the boards soldered up.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgSKpvsS-ggVAl7gVMn18koKaYu9fWU44UJI8glVPqz0KAIrN0bH0DVgahZpLOApihqoeQ6zkQeUNFTpZxqmeHtFU_NZI-V0vJR1bpBTaF0LR0h7j3tnBuU0VCSPZyalPJ3PbJS2Wtbc-4/s1600/IMG_20140827_151717.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgSKpvsS-ggVAl7gVMn18koKaYu9fWU44UJI8glVPqz0KAIrN0bH0DVgahZpLOApihqoeQ6zkQeUNFTpZxqmeHtFU_NZI-V0vJR1bpBTaF0LR0h7j3tnBuU0VCSPZyalPJ3PbJS2Wtbc-4/s1600/IMG_20140827_151717.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiZyrMxBOtxHK7sb8v5sHSc7vcSCf8GJYG9B3Os328Vu7zj3hRUWKqfyUUHX84-V5IoYm8fV0D3J4Htb-_AxQLen-dxk_oOb9HUIIVBLk6X-SllvwpyTSzZ0yklQTFvR-djAYxGxL_Z6EI/s1600/IMG_20140827_183851.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiZyrMxBOtxHK7sb8v5sHSc7vcSCf8GJYG9B3Os328Vu7zj3hRUWKqfyUUHX84-V5IoYm8fV0D3J4Htb-_AxQLen-dxk_oOb9HUIIVBLk6X-SllvwpyTSzZ0yklQTFvR-djAYxGxL_Z6EI/s1600/IMG_20140827_183851.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<span id="goog_1580345200"></span><span id="goog_1580345201"></span><br /></div>
<h3 style="clear: both; text-align: left;">
Flight testing</h3>
<div class="separator" style="clear: both; text-align: left;">
I went ahead and put it on my Iconic-X frame that had the previous BGC revision and was pleased with the results:</div>
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/104575370" webkitallowfullscreen="" width="500"></iframe> <br />
And OsoGrande put it through some more aggressive testing:
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/106104484" webkitallowfullscreen="" width="500"></iframe>
<br />
<h3 style="text-align: left;">
Features</h3>
<div style="text-align: left;">
<ul style="text-align: left;">
<li>Two axis control</li>
<li>Easy tuning and configuration via Tau Labs GCS</li>
<li>Integration with flight controller via CAN bus</li>
<li>Point of interest tracking (e.g. phone/tablet tracking)</li>
<li><a href="http://instagram.com/p/s6EJKElqlO">Lock the gimbal position during flips and rolls</a></li>
<li><a href="http://instagram.com/p/s5YnOflqi9">Relay control signals via FC using CAN</a>. Extremely convenient when you use a single wire receiver such as Spektrum Satellite.</li>
</ul>
</div>
<h3 style="text-align: left;">
Next</h3>
<div>
Now I have to connect it up via CAN and get some of the functions working like controlling the pitch angle via the transmitter and repeating the POI tracking that I have done with Oso Grande in the past.</div>
<div>
<br /></div>
<div>
<br /></div>
</div>
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/91046135" webkitallowfullscreen="" width="500"></iframe></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com40tag:blogger.com,1999:blog-1759046512792102553.post-28968213421583930862014-07-05T15:21:00.001-07:002014-07-05T15:27:26.453-07:00Soldering while traveling?<div dir="ltr" style="text-align: left;" trbidi="on">
I just want to comment on a trick I learnt last week.<br />
<br />
Last week I went to Santorini and diligently packed two quads. My <a href="http://buildandcrash.blogspot.com/2014/07/flying-spark-3d-printed-mini-quad.html">Flying Spark</a> for LOS and video recording and my <a href="http://buildandcrash.blogspot.com/2014/02/microquad-from-hovership-pro.html">Hovership MHQ</a> for FPV (or letting other people see the video stream). I thought I was pretty prepared with tons of spare parts, tools and screws:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiqViwdK130QO45vIPcNQfIgGg3h1MYbLNCL7p5hpBbD9HwdsYNabpVmpQGpOSMjfWras6YG0oar9jlPZ78a0LHVnJHO1Ze656_VAvSEvBBCY45Xt8vpJnzJoushaNOM25bRdMLIGTNDV0/s1600/IMG_20140623_091922.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiqViwdK130QO45vIPcNQfIgGg3h1MYbLNCL7p5hpBbD9HwdsYNabpVmpQGpOSMjfWras6YG0oar9jlPZ78a0LHVnJHO1Ze656_VAvSEvBBCY45Xt8vpJnzJoushaNOM25bRdMLIGTNDV0/s1600/IMG_20140623_091922.jpg" height="240" width="320" /></a></div>
<br />
Unfortunately when I got there, I had an issue with the MHQ:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjm3dpQwJmIn0kODmMbH_VB0AmljN7H7712M_yjbE-HujElR65m2dFeeeQ8T25ZdEObR7y0e2dYHCSwpnfpVL0TuOkJhFWDHIuWlz-XCyk1eW7D9IbQgWoqgpdQSOURn7ojC34cNGcDjl8/s1600/IMG_20140625_173021.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjm3dpQwJmIn0kODmMbH_VB0AmljN7H7712M_yjbE-HujElR65m2dFeeeQ8T25ZdEObR7y0e2dYHCSwpnfpVL0TuOkJhFWDHIuWlz-XCyk1eW7D9IbQgWoqgpdQSOURn7ojC34cNGcDjl8/s1600/IMG_20140625_173021.jpg" height="240" width="320" /></a></div>
<br />
Santorini isn't a huge island so my chances of finding an electronic repair shop were pretty slip. Luckily, one of my friends suggested a candle, so here was my soldering setup:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiL_xmBOFinAw9PXKKewQHBMW0QzUECwQ7kx10naUjv6uJVleKMvVVcoVPZhZ8y_WzBGiBbE9AGyFVPBWVxs7mlWpqyMmO6MpnF90TL899tbJrvN87fQ-21OtIJEebTZTYMgU-CSzdFeFw/s1600/IMG_20140628_204113.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiL_xmBOFinAw9PXKKewQHBMW0QzUECwQ7kx10naUjv6uJVleKMvVVcoVPZhZ8y_WzBGiBbE9AGyFVPBWVxs7mlWpqyMmO6MpnF90TL899tbJrvN87fQ-21OtIJEebTZTYMgU-CSzdFeFw/s1600/IMG_20140628_204113.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEircck_oqR5mZ0-WwP3DqRY_5Prp-J0XswRwUDBxUBMPJSGR1NDwOLjuxl11dAR7FhF5HUFXTGzM_dSend8LM8v77SzXEbGlHRDKAFbUw9PfJ-LGQVLH2kTNL59w3_qRoC-zL9R20V62_U/s1600/IMG_20140628_204457.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEircck_oqR5mZ0-WwP3DqRY_5Prp-J0XswRwUDBxUBMPJSGR1NDwOLjuxl11dAR7FhF5HUFXTGzM_dSend8LM8v77SzXEbGlHRDKAFbUw9PfJ-LGQVLH2kTNL59w3_qRoC-zL9R20V62_U/s1600/IMG_20140628_204457.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
It turns out the trick is that because the flame has a low heat transfer efficiency compared to a normal iron things take a lot longer. Basically it took between 3-5 minutes to get the ESC wire hot enough for the solder to flow. This also resulted in warm fingers, but the results worked!</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<br />
<br />
<br /></div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com3tag:blogger.com,1999:blog-1759046512792102553.post-19554119406171251692014-07-04T08:16:00.002-07:002014-07-07T07:56:25.975-07:00Flying Spark - 3D printed mini quad<div dir="ltr" style="text-align: left;" trbidi="on">
I've been wanting to design a 3D printed frame since having so much fun with Steve's. To cut to the chase, here is what I finished with:<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjQ8lshu3GSZQpGpxsifCN8MAvCiie1gar5gz70YHpbKh6gfkuWrvO_86UwJwzq67i4u265eG7Ri67AY_hiYbcxSmiVA30WYW4ErTALeByLIqk9lGw7mDSd9B0KTZTt3gKnYsrcZzMXqr8/s1600/IMG_20140617_225430.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjQ8lshu3GSZQpGpxsifCN8MAvCiie1gar5gz70YHpbKh6gfkuWrvO_86UwJwzq67i4u265eG7Ri67AY_hiYbcxSmiVA30WYW4ErTALeByLIqk9lGw7mDSd9B0KTZTt3gKnYsrcZzMXqr8/s1600/IMG_20140617_225430.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Without prop guards</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwRhevyNjf8lEDu-DQbLsPGzY2SRI5CZBxqPCYAhG46bHc1ByAywxdvku0LwYgZDuV0ayE3nR5WeQ_jJu3TyUa8gEGI2Qu5vGnzgd2pkuPIDDQz_6uDxgnrjteliXztWWcnKkm2EfMgbc/s1600/IMG_20140603_182153.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto; text-align: center;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwRhevyNjf8lEDu-DQbLsPGzY2SRI5CZBxqPCYAhG46bHc1ByAywxdvku0LwYgZDuV0ayE3nR5WeQ_jJu3TyUa8gEGI2Qu5vGnzgd2pkuPIDDQz_6uDxgnrjteliXztWWcnKkm2EfMgbc/s1600/IMG_20140603_182153.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Arms printed with prop guards</td></tr>
</tbody></table>
And here are some videos from it:<br />
<div>
<br />
<div style="text-align: right;">
</div>
<div style="text-align: left;">
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="300" mozallowfullscreen="" src="//player.vimeo.com/hubnut/album/2941212?color=44bbff&background=000000&slideshow=0&video_title=1&video_byline=1" webkitallowfullscreen="" width="400"></iframe>
</div>
<div style="text-align: center;">
<br /></div>
</div>
The ready to fly weight is 437g with 1500 mAh 3S batteries and mobius camera. It gets around 12 minutes of battery time with 5x3 motors although I haven't really pushed it.<br />
<br />
<div style="text-align: left;">
<span style="font-weight: normal;">You can find the design on <a href="http://www.thingiverse.com/thing:384566">Thingiverse</a></span></div>
<h3 style="text-align: left;">
Design</h3>
<div style="text-align: left;">
<span style="font-weight: normal;">I had a few requirements:</span></div>
<ul style="text-align: left;">
<li>aerodynamic shape, fairly resilient to wind</li>
<li>center of gravity near center of thrust</li>
<li>keep component on the inside (mobius, battery, sparky)</li>
<li>pack up well for traveling</li>
<li>easy to replace broken parts</li>
</ul>
<div>
The main hardware components were:</div>
<div>
<ul style="text-align: left;">
<li><a href="http://buildandcrash.blogspot.com/2013/05/sparky-testing-and-building-no-crashing.html">Sparky flight controller</a> (of course)</li>
<li>SunnySky X2204 2300kv motors (with 12A ESCs)</li>
<li>1500 mAh 3S batteries</li>
<li>Mobius video recorder</li>
</ul>
</div>
<div>
I originally started with FreeCAD but found OpenSCAD worked better for me, and was a useful new tool to learn. I started by modeling the outer hull. To decide the shape I simply took the battery, sparky and mobius and figured out the smallest way to stack them together.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlc7-rtiSJOgU7VQX2tLQpjH5KJ-ZBqHGhn1nBxEyRL-P4EErcPJqIk5aMKc03qBXDCJIETwCqQ04klBPu1FrQhA6bM3SSQ6ULuj2Eas3IjyM1PaiwuWI6PUio5mnxnNiKwX1Z5vnlrVw/s1600/IMG_20140617_224923.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlc7-rtiSJOgU7VQX2tLQpjH5KJ-ZBqHGhn1nBxEyRL-P4EErcPJqIk5aMKc03qBXDCJIETwCqQ04klBPu1FrQhA6bM3SSQ6ULuj2Eas3IjyM1PaiwuWI6PUio5mnxnNiKwX1Z5vnlrVw/s1600/IMG_20140617_224923.jpg" height="240" width="320" /></a></div>
<div>
<br /></div>
<div>
Then I modeled a nice smooth hull around that:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi8CYYs8gyam0-0W1ja_55mkVWCF6oqXgZWnU7HumiYzWk5xttWwspx75vmS_D1jZVkK23mAtvyKCD0hzdbygKI1f3UZHo4EEWGJHdEo-j-cTf1kSJj4p-9qFO4fryiKsdC5SUA65eoR98/s1600/Screen+Shot+2014-06-17+at+10.31.46+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi8CYYs8gyam0-0W1ja_55mkVWCF6oqXgZWnU7HumiYzWk5xttWwspx75vmS_D1jZVkK23mAtvyKCD0hzdbygKI1f3UZHo4EEWGJHdEo-j-cTf1kSJj4p-9qFO4fryiKsdC5SUA65eoR98/s1600/Screen+Shot+2014-06-17+at+10.31.46+PM.png" height="208" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
and the internal components, considering how to make sure the negative space would successfully print:</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEisCoWTRTP9Bv44WAKDTrqGnWW-ipRsbDUlbftb4hyphenhyphenGNF9dFR00WrxyuRxG0tS86WJRZ-zLzGyrfwjwKpjnNQw92Zal5CMIb5VpZ3y2fr3N4SKmZ5P9F4bjqMGReI1rFuPOtX0RpzqD-3c/s1600/Screen+Shot+2014-06-17+at+10.34.02+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEisCoWTRTP9Bv44WAKDTrqGnWW-ipRsbDUlbftb4hyphenhyphenGNF9dFR00WrxyuRxG0tS86WJRZ-zLzGyrfwjwKpjnNQw92Zal5CMIb5VpZ3y2fr3N4SKmZ5P9F4bjqMGReI1rFuPOtX0RpzqD-3c/s1600/Screen+Shot+2014-06-17+at+10.34.02+PM.png" height="232" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Giving the main chassis as the difference between the two:</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjpZeeOYD0vU1aJFEOdQqBRZcdsSUPlQvpM5Qg49l2ifgy1QQmdvDxQCZCvYZcYe3rny-hnqxHhPU_yLIuhifikUsgp5t6QL91lU7fFC2PTff82hnYrJNYLYy6Dpl4Zbi2M0P76fbquTeI/s1600/Screen+Shot+2014-06-17+at+10.33.40+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjpZeeOYD0vU1aJFEOdQqBRZcdsSUPlQvpM5Qg49l2ifgy1QQmdvDxQCZCvYZcYe3rny-hnqxHhPU_yLIuhifikUsgp5t6QL91lU7fFC2PTff82hnYrJNYLYy6Dpl4Zbi2M0P76fbquTeI/s1600/Screen+Shot+2014-06-17+at+10.33.40+PM.png" height="201" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
As well as arms that can be plugged into the sockets, with a split in the middle to decrease resistance to airflow. You can also see in the above images that I made a variant with prop guards.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEha3W_k3rtJg04sHG6YK0tEmAAGZZsafhggVxmxbLC6kGpmltT-8YofkMwOEQorcJrXAbzL50_a3rmFymW2GXxkbr_IEF02RiIXj8UO3TYDHGD_QSC72bJdV5fyAty2G42A0B5NMsMHJvw/s1600/Screen+Shot+2014-06-17+at+10.26.27+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEha3W_k3rtJg04sHG6YK0tEmAAGZZsafhggVxmxbLC6kGpmltT-8YofkMwOEQorcJrXAbzL50_a3rmFymW2GXxkbr_IEF02RiIXj8UO3TYDHGD_QSC72bJdV5fyAty2G42A0B5NMsMHJvw/s1600/Screen+Shot+2014-06-17+at+10.26.27+PM.png" height="202" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h3 style="text-align: left;">
Printed model</h3>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi27Kp-Jc0BwBdPhEPREk4HQDdUlqtcUHRbvjWK1Slp9dmvI6Pu0feX0nmnyHztDi-_g1k6D8Zcexxn8Rt5A3_dtT20il7tgF-XeXRZNo0dhiDjtt8igGxdWaKb7l1gB13m4-j6dRu1ceM/s1600/IMG_20140617_225258.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi27Kp-Jc0BwBdPhEPREk4HQDdUlqtcUHRbvjWK1Slp9dmvI6Pu0feX0nmnyHztDi-_g1k6D8Zcexxn8Rt5A3_dtT20il7tgF-XeXRZNo0dhiDjtt8igGxdWaKb7l1gB13m4-j6dRu1ceM/s1600/IMG_20140617_225258.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Printed with 3 shells and 30% infill the printed parts weigh 122 g.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2kzQa7Vtr2ghLLUOXU5I5X31HrT9-IgNebUFbTvVqKRXTEYvOlUO8h_O6o8iAppSv7qhwfvOrPI7IDr6VIsWJcSppuE8BZ7nIQSSpEPaRRnf0EuedIcWeEn5ZBhOoFo2d_pxJHB_GQ7w/s1600/IMG_20140617_224952.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2kzQa7Vtr2ghLLUOXU5I5X31HrT9-IgNebUFbTvVqKRXTEYvOlUO8h_O6o8iAppSv7qhwfvOrPI7IDr6VIsWJcSppuE8BZ7nIQSSpEPaRRnf0EuedIcWeEn5ZBhOoFo2d_pxJHB_GQ7w/s1600/IMG_20140617_224952.jpg" height="240" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjPcScm4ayieEG5dsgxtR7Zx9TAHo_Ipx_QK4vVWCcXwB2FyMWiY_ReEpYc-F3oT4JbIbKD21AILmIVA6x_5C1_eEgwHuBvdxqarQq_fNRTLSqQiqaTxKMpri6v_HdY9ydyVFLLUUlvml4/s1600/IMG_20140617_225744.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjPcScm4ayieEG5dsgxtR7Zx9TAHo_Ipx_QK4vVWCcXwB2FyMWiY_ReEpYc-F3oT4JbIbKD21AILmIVA6x_5C1_eEgwHuBvdxqarQq_fNRTLSqQiqaTxKMpri6v_HdY9ydyVFLLUUlvml4/s1600/IMG_20140617_225744.jpg" height="240" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiuIueXz5-vyeEEGPEYE-HxXpeTLixLiEFHCBiczbV0Ic8KsjpX1edsi8OONJRnPvw8P-uEsAKEAi-m_AqefR8qC0pNQPTZlzHEFV9YT4oeORaGp_dgj-ZwmPNQVCXZ96HW0uAq_sGPmwM/s1600/IMG_20140617_225013.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiuIueXz5-vyeEEGPEYE-HxXpeTLixLiEFHCBiczbV0Ic8KsjpX1edsi8OONJRnPvw8P-uEsAKEAi-m_AqefR8qC0pNQPTZlzHEFV9YT4oeORaGp_dgj-ZwmPNQVCXZ96HW0uAq_sGPmwM/s1600/IMG_20140617_225013.jpg" height="240" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi-XP5NnvKeTt7YI7yNifa2qdb69Uw31qtrotRGl4uWZdIMjRggB_y_KKOoRdJRT8h_Pcdnaof3RvcfJ9d4MJ-O7_my6DAHK6yuNIZ_COe7KD37rO23mkrH9xNTF9AiXpudmx0i8-8JFq0/s1600/IMG_20140617_225107.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi-XP5NnvKeTt7YI7yNifa2qdb69Uw31qtrotRGl4uWZdIMjRggB_y_KKOoRdJRT8h_Pcdnaof3RvcfJ9d4MJ-O7_my6DAHK6yuNIZ_COe7KD37rO23mkrH9xNTF9AiXpudmx0i8-8JFq0/s1600/IMG_20140617_225107.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgw9hY7T-3QM8xfU8CXN7S1Rd6OejKULiNzCA5OvVTCzXte3GpV5-1Yn1H63h0CGxcLuxC151-Qp_frqF9pnf7qqWySLfskIdVtTRf3_uX7bG1VbUwhoQjZ-g6r8YdQQZoPUjctV_rlzVk/s1600/IMG_20140707_091030.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgw9hY7T-3QM8xfU8CXN7S1Rd6OejKULiNzCA5OvVTCzXte3GpV5-1Yn1H63h0CGxcLuxC151-Qp_frqF9pnf7qqWySLfskIdVtTRf3_uX7bG1VbUwhoQjZ-g6r8YdQQZoPUjctV_rlzVk/s1600/IMG_20140707_091030.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
and it packs up pretty nicely for traveling (remove 4 screws and arms pull out of sockets) if you need to disassemble it (e.g. for going into checked luggage).</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEib2brbmEMxJcGZmvY2UuNJBf5_feGoHWhlzMHTcx9gl2BJ5erTRKqZ9mff9XNK91ZPvjV7Tk1DRH4CGo84L8-pCvsXc5SJo59MZQHoE3Ocit-zU_NbxIP5vnwviLxlZ5rP3JiKyGv6BNA/s1600/IMG_20140623_120750.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEib2brbmEMxJcGZmvY2UuNJBf5_feGoHWhlzMHTcx9gl2BJ5erTRKqZ9mff9XNK91ZPvjV7Tk1DRH4CGo84L8-pCvsXc5SJo59MZQHoE3Ocit-zU_NbxIP5vnwviLxlZ5rP3JiKyGv6BNA/s1600/IMG_20140623_120750.jpg" height="320" width="240" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
<br /></div>
<h3 style="text-align: left;">
Flight performance</h3>
<div>
<div style="text-align: left;">
So of course, the first thing I did was run the latest version of autotuning: </div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: left;">
, which gave these properties and PID settings:</div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhEn3UOO1sz8t-TNzgm099fWXp_3DwZXzGo1BQ6V-jOCWzsc0Ta5EziEUbiEy-ibSaZ8AXuNPQXrXpDWHbBpTcuMS_nsqdWfG84OqcA7rgV1ww3ursa4eWaOwawsafThW1dV7T36tK-Rbg/s1600/Screen+Shot+2014-07-03+at+7.50.16+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhEn3UOO1sz8t-TNzgm099fWXp_3DwZXzGo1BQ6V-jOCWzsc0Ta5EziEUbiEy-ibSaZ8AXuNPQXrXpDWHbBpTcuMS_nsqdWfG84OqcA7rgV1ww3ursa4eWaOwawsafThW1dV7T36tK-Rbg/s1600/Screen+Shot+2014-07-03+at+7.50.16+PM.png" height="179" width="320" /></a></div>
<br />
I was really pleased with the performance of the autotune algorithm actually, it was really windy where I was traveling and I tried manually tuning it and couldn't beat the performance for flying well but not twitching in response to the wind.<br />
<br />
It responds quite symmetrically. It also has a ton of pop. In fact, when I first tested it indoors and gunned it, I had a nice collision with the roof. This was flying the prototype arms printed with 10% infill:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgy5t7zIy3kBTt4wfbK34QqXTYSQ3iVZuEuWz6WGWnjgulVLMskADIuZ7ucGrZK8YZB8McU7QndaDLfnUcSVb3nkYbJJ67TzCgynR-I_uBdHZ9E4vtmDPatj-V3qKaJH_JON_Uxgjq9H3c/s1600/IMG_20140612_175806.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgy5t7zIy3kBTt4wfbK34QqXTYSQ3iVZuEuWz6WGWnjgulVLMskADIuZ7ucGrZK8YZB8McU7QndaDLfnUcSVb3nkYbJJ67TzCgynR-I_uBdHZ9E4vtmDPatj-V3qKaJH_JON_Uxgjq9H3c/s1600/IMG_20140612_175806.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
However, the 30% fill are a lot more robust and so far I haven't managed to break one. As I mentioned, the main purpose way to travel well, and I was really pleased with that. Using 65mm (from edge of frame to center of motor) arms it would drop in my small backpack with props on and had no issues. The problem with that length is it leaves a tiny bit of blade in the frame. The 75mm arm does not, but wouldn't quite fit in my backpack. I might try modifying the chassis to move the arm back 5 mm which should fix it.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<h3 style="clear: both; text-align: left;">
Videos</h3>
<div>
As I mentioned, this quad was largely designed to be small, travel well, and behave in the wind. I took it to a conference in Santorini which really put those things to the test. I'm really quite pleased with the results. Here are some videos:</div>
<div>
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/99929749" webkitallowfullscreen="" width="500"></iframe> <br />
<br />
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/99939830" webkitallowfullscreen="" width="500"></iframe>
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/99941770" webkitallowfullscreen="" width="500"></iframe>
</div>
<br /></div>
</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com2tag:blogger.com,1999:blog-1759046512792102553.post-18791201132855122272014-03-23T10:19:00.001-07:002014-03-23T10:21:31.104-07:00Vertical control<div dir="ltr" style="text-align: left;" trbidi="on">
Vertical control is still not at a state that I'm happy with. We recently took <a href="https://github.com/TauLabs/TauLabs/pull/1080">one very important step</a> in the right direction by making the same code and settings be used for standalone altitude control and navigation altitude control. At least with this, there is only one thing that requires tuning. After a fair bit of work, I'm pretty happy with the result. If you just want to see the video here it is<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/89844044" webkitallowfullscreen="" width="500"></iframe>f</div>
<br />
<h2 style="text-align: left;">
Sixteen state INS</h2>
One issue I see is that the accelerometer bias is not reproducible enough flight to flight, and because this is integrated into velocity that creates a non-trivial amount of noise. In the review I linked above, the complementary filter that is used for the vertical axis (based on ardupilot, to give credit where it is due) estimates the accelerometer bias. However, when running navigation (and thus the INS algorithm) the bias is not tracked for the accelerometers. The most obvious consequence of this is when you enable position hold mode or something else you initially get a throttle surge or dip. After it drops enough, the outer position control kicks in and the you get about a reasonable behavior.<br />
<br />
One solution to this, which has already been merged, is the <a href="https://github.com/TauLabs/TauLabs/pull/1001">zero accel button</a>. This will let you correct this error, but because the bias changes flight to flight will only be a short term fix.<br />
<br />
This is more of a problem, though, for landing when only the velocity is controlled. If the decent rate is 1 m/s and the velocity axis has a 0.5 m/s error you get quite a large error in landing rate and either a long wait or quite a bump.<br />
<br />
We had previously played around with a 16 state INS that added the accelerometer bias but it did not work terribly well. One issue for this was that when the board is sitting still, there is essentially a manifold of valid states - the board could be upside down if the accel bias were set to 16 m/s^2, for example. Unobservable systems are <b>very</b> bad for control. There was a fairly simple way of fixing this: I made the state equation for X and Y accel biases have a drift towards zero. This allows it to get to non-zero values (when flying around and really accelerating there might be good evidence for it) but keeps those values fairly well grounded near zero. This is appropriate, too, because the accel bias does not get that far from zero with a reasonably calibrated system.<br />
<br />
The second problem turned out to be some bugs in the automatically generated efficient version of the covariance prediction. Manually finding the five typos in this wall of code (and this is only about a third of it)<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEilpCsJOPmd0Ii1HFDLlxoG-T-DmaHbbV09aV6wPjZw4SW_oFOevU6dtlVXYR4ctPQtfUz7vRYEuUDjg4h1Ez7t2cRwzZUMinCqs0z4k90rZbNwvImZUqDIwq_9vNG3StuzvlavHzF8zF0/s1600/Screen+Shot+2014-02-23+at+5.58.30+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEilpCsJOPmd0Ii1HFDLlxoG-T-DmaHbbV09aV6wPjZw4SW_oFOevU6dtlVXYR4ctPQtfUz7vRYEuUDjg4h1Ez7t2cRwzZUMinCqs0z4k90rZbNwvImZUqDIwq_9vNG3StuzvlavHzF8zF0/s1600/Screen+Shot+2014-02-23+at+5.58.30+PM.png" height="203" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
was not the most fun I've had in the last few weeks. However, after fixing that and a few other tweaks it seems to be working quite well. Manually miscalibrating the system with an accelerometer bias of even 1 m/s^2 is accounted for perfectly and after thirty seconds the error in the vertical velocity falls to less than 0.1 m/s.<br />
<br />
Of course, going to a 16 state INS introduces a higher CPU and memory load. However, on Sparky the INS is still only less than 1/4 of the CPU utilization which seems reasonable if it results in a good state.<br />
<br />
<h3 style="text-align: left;">
INS Testing and tuning</h3>
<div>
<br /></div>
To test this version of the INS, I got some logs with the Overo on <a href="http://buildandcrash.blogspot.com/2012/11/assembly-and-first-flight.html">Freedom</a> and visualized the output of the INS and the quad movement. It seems to track quite well:<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/89117769" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Now one issue I'm running into is that when I tune the baro variance to make sure it does track the altitude well, that couples the noise from the baro into the velocity estimate. This seems to be limiting the tuning settings I can get away with.<br />
<br />
<h2 style="text-align: left;">
</h2>
<h2 style="text-align: left;">
Vibrations and Fourteen state INS</h2>
<div>
<br /></div>
<div>
Since the main issue bias we have issue with is the vertical, at least for now, I wanted to try and not burn cycles on the horizontal biases (although it is quite possible we might go back on this eventually). With some help from Dale (the original INS author) I jumped in and modified it to a fourteen state estimator, with only the vertical bias term being tracked. This wasn't too hard in the end, and also does a great job of estimating the vertical velocity.</div>
<div>
<br /></div>
<div>
However, no matter what settings I used, the vertical hold was not as good as I wanted. Interestingly, it was much better on my micro-quad. I finally broke down and moved Freedom from my POS HT-FPV frame that shakes like crazy to my QAV500. I hadn't flown this much because the pancake motors on it were not playing nicely with my ESCs and I hadn't had the time to tune them up. However, I switched to some SimonK ESCs:<br />
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi9nyfrpDv2-gD5jJEgXm6nadco0FinMFsX-s_G85gDAVjsh-jU7dZDVVnOC6mS5Wsf961V5AE5CqUejI3eLMCuSda-79nEAww8nFNiSCmn_BFRgICk9LG72BpWksi3FQw8AsfcnC9W0us/s1600/IMG_20140321_130545.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi9nyfrpDv2-gD5jJEgXm6nadco0FinMFsX-s_G85gDAVjsh-jU7dZDVVnOC6mS5Wsf961V5AE5CqUejI3eLMCuSda-79nEAww8nFNiSCmn_BFRgICk9LG72BpWksi3FQw8AsfcnC9W0us/s1600/IMG_20140321_130545.jpg" height="240" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh8wzY7JxRwSGYbrWeN2m85Kehauq4BSTnKmZiiMqbXjHGMuL9FgWoSlQsSD_2YIv5ehRmlOHMBPgVqELoXiocZtTTL-MfZadG1gSlVPCipqi4hROvO4RGCvgVQBXOF1Mg8zBeQfqM5BMQ/s1600/IMG_20140321_135254.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh8wzY7JxRwSGYbrWeN2m85Kehauq4BSTnKmZiiMqbXjHGMuL9FgWoSlQsSD_2YIv5ehRmlOHMBPgVqELoXiocZtTTL-MfZadG1gSlVPCipqi4hROvO4RGCvgVQBXOF1Mg8zBeQfqM5BMQ/s1600/IMG_20140321_135254.jpg" height="240" width="320" /></a></div>
<div>
<br />
And now no motor failures in flight. With this frame, suddenly the altitude control was much better. This was true using both the complementary filter and the new 14 state INS.<br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/89844044" webkitallowfullscreen="" width="500"></iframe>
</div>
<h2 style="text-align: left;">
Tuning</h2>
<div>
You can do all this tuning in the default StateEstimation (complementary, raw) which runs the simple inertial filter for vertical. Once the updated INS is merged you can also tune in INSIndoor mode, but for now I would avoid that with the 13 state since the velocity bias makes the next step a bad idea.</div>
<div>
<br /></div>
<div>
Next, the altitude control loop should be tuned. Ultimately I found the default values were pretty close to what I wanted but the exercise was interesting. Lux (in IRC) recommended a method from baseflight which is very analogous to how I recommended tuning the main control loop (see <a href="https://vimeo.com/25742413">this video</a> for a tutorial I did years ago).</div>
<div>
<br /></div>
<div>
Basically first you set the AltiudeHoldSettings.AltitudeKp to zero and fly altitude hold. In this condition it will drift up and down a bit randomly but should behave essentially well. Then you gradually increase the AltiudeHoldSettings.VelocityKp until the motors begin to hunt and sound really twitchy. Once you hit that point bring it back down a bit. I didn't feel the need to tune the Ki component since it seemed to be working fairly well and not overshooting.</div>
<div>
<br /></div>
<div>
Once that is done, then you can dial in the AltitudeHoldSettings.AltitudeKp again. If the altitude is wandering too much then increase that term. If the whole system is jumping up and down and hunting again, then reduce it. I found the default value of 1 or down to 0.5 seems to be a pretty good range.<br />
<br />
<b>TL;DR</b>: set Velocity Ki to about 1/5 of Velocity Kp and increase that until you see fast twitches, then back off. Then increase the outer gain until you start seeing oscillations and back off.</div>
<div>
<br /></div>
<div>
<h2 style="text-align: left;">
Vertical Control</h2>
</div>
<div>
<br /></div>
<div>
KipK in IRC also asked for more aggressive control of altitude when flying altitude hold mode. This has been on my TODO list for a while, and I kept putting it off.</div>
<div>
<br /></div>
<div>
The current scheme waits for the stick to move out and then into the middle range to enable vario mode, but most people have found this unintuitive. Instead I went ahead and added an exponential to the range outside the dead band. This allows more sensitive control in the middle and aggressive control for further stick movements.</div>
<div>
<br /></div>
<div>
Previously, moving the sticks only shifted the set point. Instead I wanted something more like AxisLock where in the middle range the setpoint stays the same and in the outer range you control rate instead of moving the setpoint. In control parlance this is called full state control where we pass the desired position and rate.</div>
<div>
<br /></div>
<div>
I thought I was pretty clever coming up with this scheme, but looking around it seems like everyone has converged on it for vario mode - which probably means it is a reasonable idea.<br />
<br />
Here is a video of OsoGrande testing it out and then myself. I'm pretty happy with the response and he said it felt fairly natural to fly.<br />
<br /></div>
<div>
<div style="text-align: center;">
<iframe allowfullscreen="" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/88549064" webkitallowfullscreen="" width="500"></iframe>
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/88439963" webkitallowfullscreen="" width="500"></iframe>
</div>
<br />
There was also a glitch with vertical control when doing position hold and RTH that caused it to have a brief dip when engaged. The integral wasn't being properly preloaded with the hover throttle, but this should be <a href="https://github.com/TauLabs/TauLabs/pull/1154">fixed now</a>.<br />
<h2 style="text-align: left;">
Conclusion</h2>
</div>
<div>
<br /></div>
<div>
So with all these changes, I think we are set to have some really clean navigation. Some care needs to be taken of vibration if you want to get a really clean hover. This is much easier on smaller quads in my experience.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com10tag:blogger.com,1999:blog-1759046512792102553.post-66235992357555776192014-03-22T21:25:00.000-07:002015-05-13T15:18:38.111-07:00Magnetometer handling in INS<div dir="ltr" style="text-align: left;" trbidi="on">
<script type="text/x-mathjax-config">
MathJax.Hub.Config({tex2jax: {inlineMath: [['$','$'], ['\\(','\\)']]}});
</script>
<script src="http://cdn.mathjax.org/mathjax/latest/MathJax.js?config=TeX-AMS-MML_HTMLorMML" type="text/javascript">
</script>
<br />
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
The Tau Labs INS (written by Dale Schinstock) works really well and has been used for various navigation tasks for the last few years. However, one aspect that I have found problematic is the magnetometer handling. The way it works currently is that the Earth's 3D magnetic vector is rotated by the attitude to predict the 3D measurement we should get.<br />
<br />
In principle that is a great idea, and on planes probably fine. However, on multirotors that generate a lot of local field distortions from the motors, it is rather problematic. The reason is that as the Z (down) component is altered, it creates a bias in the roll and pitch components of attitude to deal with this. We already know (from years of experience flying the complementary filter) that the gyros and accels are sufficient to stabilize those components. As a work around we generally have just used fairly high variances for the magnetometer. This isn't optimal though, as I've seen the INS bias estimate for the Z axis sometimes destabilize since it isn't sufficiently constrained by the mag when initially converging if things are fairly miscalibrated.<br />
<br />
I have been wanting to alter the EKF for some time to only allow the magnetometer to influence the heading estimate, but the path wasn't obvious. Today I decided to sit down and implement this, and I'm fairly happy with the result.<br />
<br />
<h2 style="text-align: left;">
Derivation</h2>
<div>
<br /></div>
<div>
We want to measure just the heading aspect of the mag, in order to get rid of the mag influencing attitude. Currently the predicted measurement of the magnetometer is </div>
<div>
<br /></div>
<div>
$\bar B_b = R_{be}(q) Be$<br />
<br /></div>
So we want a version that only depends on the <i>heading </i>component of $q$. That turns out to be less trivial that it sounds. To achieve this, we essentially want to only work with magnetic information projected into a plane parallel to the earth (called the $h$ plane). The rotation $R_{be}$ can be decomposed into two matricies, $R_{be}=R_{bh} R_{he}$, where $R_{bh}$ applies the pitch and roll transformation and $R_{he}$ applies the yaw transformation. We can rotate the raw mag measurements in order to undo the influence of just the roll and pitch by using the inverse (in this case transpose) of $R_{bh}$, $B_h = R_{bh}^T B$, and then only keep the components in x and y.<br />
<br />
To calculate both $R_{bh}$ and $R_{he}$, we can get the equations from <a href="https://github.com/TauLabs/TauLabs/blob/next/flight/Libraries/math/coordinate_conversions.c#L131">the code</a>. I then used this code in matlab and the symbolic toolbox to get the matrix. It took a little bit of massaging afterwards to get an efficient implementation:<br />
<br />
<pre class="brush:matlabkey">syms q1 q2 q3 q4 real
q = [q1 q2 q3 q4];
q0s = q(1) ^ 2;
q1s = q(2) ^ 2;
q2s = q(3) ^ 2;
q3s = q(4) ^ 2;
R13 = 2.0 * (q(:,2) .* q(:,4) - q(:,1) .* q(:,3));
R11 = q0s + q1s - q2s - q3s;
R12 = 2.0 * (q(:,2) .* q(:,3) + q(:,1) .* q(:,4));
R23 = 2.0 * (q(:,3) .* q(:,4) + q(:,1) .* q(:,2));
R33 = q0s - q1s - q2s + q3s;
roll = atan2(R23, R33)
pitch = asin(-R13)
yaw = atan2(R12, R11)
% compute the rotation matrix that is for the attitude component
% this is the matrix that will rotate from the earth frame to the
% current roll and pitch. The inverse will take the magnetometer
% reading back into a horizontal place
sF = sin(roll); cF = cos(roll);
sT = sin(pitch); cT = cos(pitch);
r = sqrt(R23^2 + R33^2)
sF = R23 / r;
cF = R33 / r;
sT = -R13;
cT = sqrt(1 - R13^2);
Rbe_bh = [cT, 0, -sT;
sF*sT, cF, cT*sF;
cF*sT, -sF, cT*cF]
</pre>
<br />
Then we need to modify the EKF to predict a measurement in the horizontal plane. That aspect is pretty straighforward, it is the same equation but keeping the yaw component instead of pitch and roll<br />
<br /></div>
<pre class="brush:matlabkey">% direct equation
sP = sin(yaw); cP = cos(yaw);
Rbe_h = [cP, sP;
-sP, cP];
% another expression that results in code that doesn't use imaginary
% numbers
x = R12;
y = R11;
r = sqrt(R12^2 + R11^2)
Rbe_h = [y/r x/r; -x/r y/r];
% calculate predicted B_h in the horizontal plane
B_h = Rbe_h * Be
% generate c code to compute this
ccode(B_h)
</pre>
<br />
I ended up having to manually expand $cos(atan2(x,y))=\tfrac{y}{\sqrt{x^2+y^2}}$ for matlab because it kept trying to use imaginary numbers to calculate the norm. The last line of this actually generates C code for the two components of $B_h$. It needed a fair bit of massaging after that to factor out common terms and get an efficient implementation.<br />
<br />
The other thing needed for the INS is the derivative of the measurements with regard to the state, or in this case $\tfrac{\delta B_h} {\delta \mathbf{q}}$.<br />
<br /></div>
<pre class="brush:matlabkey">% and compute the derivatives wrt to the attitude
ccode([diff(B_h,q0)'; diff(B_h,q1)'; diff(B_h,q2)'; diff(B_h,q3)'])
</pre>
<br />
Again, Matlab symbolic toolbox to the rescue, saving me from a lot of tedious algebra, although again lots of massaging was required.<br />
<br />
<h2 style="text-align: left;">
Testing</h2>
<div>
<br /></div>
<div>
So again, Freedom Overo logs saved me tons of time, since I can replay previous flights through the new filter and see how it performs. It performs <i>really nicely</i>. The nice thing about this, is we can tighten up the variances on the mag and make sure the convergence behaves well, and not worry about the magnetic field biasing the attitude as we go.</div>
<div>
<br /></div>
<div>
Here is the raw magnetic heading and the INS output:</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiSMAXeIFXIaHdd-6n_5NwGcpiCWvIichiBPft2-SmIPW5YbSOHj2-TLQaYEnwucfZcDPEvS_EAyR_ustSaL35VtqPUVUK37ohbF9urQjO6y9_QjhaMqrZM0ou3IxFBfrdookYS9O7zPO8/s1600/Screen+Shot+2014-03-23+at+12.00.45+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="180" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiSMAXeIFXIaHdd-6n_5NwGcpiCWvIichiBPft2-SmIPW5YbSOHj2-TLQaYEnwucfZcDPEvS_EAyR_ustSaL35VtqPUVUK37ohbF9urQjO6y9_QjhaMqrZM0ou3IxFBfrdookYS9O7zPO8/s1600/Screen+Shot+2014-03-23+at+12.00.45+AM.png" width="640" /></a></div>
<div>
<br /></div>
<div>
, which you can see is nicely tracking together.<br />
<br />
I also loaded it up on my Freedom and power cycled it a bunch of times, as well as letting is sit for an hour. Rock solid - none of the oscillations I would sometimes see with the previous code - and now I can keep the gyro bias estimation on reliably. With a good accel calibration and board leveling, you get a perfect PFD:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhc7QYmcLNkCiH0Qx2EZriSUXShZuDKWYyHNsfVZjdUpTmztgapaV1tIpcdW7RM8tpX4v2Z2qOSMVU6zq1aBiPRO686xF12elyC9kpHM8rUE_C1lRpHHfVpm_IT-MJrV3hSE6fsOUqbM6k/s1600/Screen+Shot+2014-03-23+at+12.17.00+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" height="217" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhc7QYmcLNkCiH0Qx2EZriSUXShZuDKWYyHNsfVZjdUpTmztgapaV1tIpcdW7RM8tpX4v2Z2qOSMVU6zq1aBiPRO686xF12elyC9kpHM8rUE_C1lRpHHfVpm_IT-MJrV3hSE6fsOUqbM6k/s1600/Screen+Shot+2014-03-23+at+12.17.00+AM.png" width="320" /></a></div>
<br /></div>
<div>
<br /></div>
<div>
This is with minimal tuning or tweaking, so that is great. I'll need to play around with a bit in flight but I'm pretty optimistic about this - and hopefully it will reduce the rare times we do see toilet bowling. I also now need to play around again with the mag compensation code, although hopefully it won't be necessary.</div>
<div>
<br />
It was also a really fun day project. I've played with kalman filters before but never had to go quite as deeply into the extended kalman filter. I also learned some more about playing with quaternions and rotation matricies, so that was productive.</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com1tag:blogger.com,1999:blog-1759046512792102553.post-1084701992481544592014-03-15T11:26:00.004-07:002014-03-15T11:26:45.529-07:00Logging and Python parsing<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<h2 style="text-align: left;">
Current state</h2>
<div>
<br /></div>
One really common task for anything beyond normal LOS and FPV flying, is the need to analyze log files. We have a fairly nice facility for doing this - using Matlab to parse log files. Running <code> build matlab </code> generates <code>LogConvert.m</code> that will parse log files into .mat files for analysis. That works quite well, but there are a few problems:<br />
<br />
<ol style="text-align: left;">
<li>not everyone has matlab (although octave is free)</li>
<li>you need a <code>LogConvert.m</code> that matches the git hash you have</li>
<li>impossible to make standalone applications using this</li>
<li>matlab is terribly slow for processing video or generating videos</li>
<li>slow for parsing the high resolution overo logs, as well as lacking the CRC checks </li>
</ol>
<div>
Luckily, Stac came to the rescue.</div>
<div>
<br />
<h2 style="text-align: left;">
Getting logs</h2>
</div>
<div>
<br /></div>
<div>
<div>
So the easiest way to get logs is through Android (it logs all connected flights) or with GCS. This is what I'd recommend for most people.<br />
<br />
But what do you do if you want better data. My goto option is Freedom which logs <i>everything</i> and I think is awesome. However, since I haven't finished that or made more than 2 that doesn't help most people.</div>
<div>
<div dir="ltr" trbidi="on">
</div>
</div>
</div>
<div>
<br /></div>
<div>
Another option is something I came up with a <a href="http://buildandcrash.blogspot.com/2013/11/easy-logging-with-openlog.html">while ago,</a> using OpenLog. It's limited but useful. </div>
<div>
<br /></div>
<h2 style="text-align: left;">
Python parsing and plotting</h2>
<div>
<br /></div>
<div>
He wrote a python version of the code for parsing log files, that detects the appropriate git hash from the log file, checks out the xml files defining those UAV objects and generates the needed classes on the fly. The sort of really cool run time class generation python can do. This was merged <a href="https://github.com/TauLabs/TauLabs/pull/1108">here</a>.</div>
<div>
<br /></div>
<div>
To parse a log file that was generated from either Android or the GCS, simply run (from the Tau Labs repository directory):<br />
<br /></div>
<div>
<code> $ python python/logview.py path/to/file.tll</code>
</div>
<div>
<br /></div>
This launches an IPython environment - an interactive python environment - where you can proceed with data analysis and visualization. It should give you a prompt like this:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiygf0cTmj7KADx9fGo6T7x8iOIzbwMdeZg9hWI__GQ0JhpM4duPbVM_qUF8zhzCtX7CReSGaceKtLEnKHMIO3B4MAD8PLBjMO3izqW_ocYirSLb5fbn1zG5DLrWobiVsUOludRQJRCYxU/s1600/Screen+Shot+2014-03-15+at+12.12.43+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiygf0cTmj7KADx9fGo6T7x8iOIzbwMdeZg9hWI__GQ0JhpM4duPbVM_qUF8zhzCtX7CReSGaceKtLEnKHMIO3B4MAD8PLBjMO3izqW_ocYirSLb5fbn1zG5DLrWobiVsUOludRQJRCYxU/s1600/Screen+Shot+2014-03-15+at+12.12.43+PM.png" height="108" width="320" /></a></div>
<br />
There will be a few variables in your workspace at this point. The most important is <code>uavo_list</code>, which contains all of the parsed log entries of all the object types. To get the data from a particular UAVO, use the <code>as_numpy_array</code> method. You have to pass it the <code>UAVO_ObjectName</code> which is the class to cast the appropriate elements too. This will create a <code>numpy.ndarray</code> that can be indexed like a set. For example, to get the accelerometer data and plot the z component:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCdGwHXuOyB6mCrbqC7OMe_j3i97npq3UVcLVmwl6KrmUND1khBNnifjg_aHvMqkv1YBFN-uaJLBctlerXFZcErFUTVMs7LHH9f6O4-TPbojwsWhTKJ5kHdomLxDYK5g8PryT0tp3V8hg/s1600/Screen+Shot+2014-03-15+at+12.22.07+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjCdGwHXuOyB6mCrbqC7OMe_j3i97npq3UVcLVmwl6KrmUND1khBNnifjg_aHvMqkv1YBFN-uaJLBctlerXFZcErFUTVMs7LHH9f6O4-TPbojwsWhTKJ5kHdomLxDYK5g8PryT0tp3V8hg/s1600/Screen+Shot+2014-03-15+at+12.22.07+PM.png" height="138" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjLNByf2jSXligtJYeC-7WDtyWAo3jdvjh_I_JdKWf0QX3udEC73nHR07wfyG8Zb62dmhxGjWJO7EPiHRQOvvsh0WBly1fbR7beYAFgTTDj6TjTBqSekG-iliTQb1vRK9lifcLwHfG_8ZY/s1600/Screen+Shot+2014-03-15+at+12.22.21+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjLNByf2jSXligtJYeC-7WDtyWAo3jdvjh_I_JdKWf0QX3udEC73nHR07wfyG8Zb62dmhxGjWJO7EPiHRQOvvsh0WBly1fbR7beYAFgTTDj6TjTBqSekG-iliTQb1vRK9lifcLwHfG_8ZY/s1600/Screen+Shot+2014-03-15+at+12.22.21+PM.png" height="163" width="320" /></a></div>
<br />
I won't delve further into the details of plotting in python since I'm sure that is covered better elsewhere.<br />
<br />
However, a side note for processing either Overo logs or logs recorded with <a href="https://www.sparkfun.com/products/9530">OpenLog</a> and my <a href="https://github.com/peabody124/TauLabs/tree/logging">Logging branch</a>. In these files there are two differences: they enable the embedded timestamps in the UAVTalk message (described <a href="https://github.com/TauLabs/TauLabs/wiki/Development-UAVTalk-Protocol">on the wiki</a>) and do not write the githash into the file. The later is pretty annoying because you have to keep track of what version of the firmware your log files were created with, so hopefully I can fix that later. To parse these log files use this command<br />
<br />
<code> $ python -t -g GITHASH_OR_BRANCH_NAME python/logview.py path/to/file.tll</code>
<br />
<br />
The -t switch tells it to use the internal timestamps (which are more accurate since they are when the FC sent the data) and the second part tells it what git hash to get the set of xml files from.<br />
<br />
<h2 style="text-align: left;">
Generating videos</h2>
<div>
<br /></div>
<div>
I've been developing a set of methods that take these log files and generate a video of graphs. Just for general analysis, I find overlaying data on top of the video of flight is really informative. I also think this could evolve into a cool set of overlays for FPV flights.</div>
<div>
<br /></div>
<div>
At the core of this is the <code>matplotlib.animation</code> library. You write a function that will plot (or manipulate a plot) to what you want at a given time stamp. For example I often shift plots to center at that time stamp and show a brief segment around it, with markers centered at the current time:<br />
<br />
<pre># Plot a segment of the path
def update_img(t, mark_0=mark_0, mark_1=mark_1, mark_2=mark_2, ax=ax):
# convert to minutes
t = t / 60
import matplotlib.pyplot
matplotlib.pyplot.xlim(t - 0.25, t + 0.25)
mark_0[0].set_xdata([t,t])
mark_1[0].set_xdata([t,t])
mark_2[0].set_xdata([t,t])
</pre>
<br />
Then you want to run this over a set of times and generate the video. To do this, I use this something like this:<br />
<br />
<pre>fps = 30.0
dpi = 150
t = arange(t0_s, t1_s, 1/fps)
ani = animation.FuncAnimation(fig,update_img,t,init_func=init,interval=0,blit=False)
writer = animation.writers['ffmpeg'](fps=30)
ani.save(output_filename,dpi=dpi,fps=30,writer=writer,savefig_kwargs={'facecolor':'green'})
</pre>
<br />
The <code>blit=False</code> and this set of codecs seems to work pretty well for OSX, but your mileage may vary. Now, because I'm typically wanting to use this to create an overlay, I use a green background everywhere. If I have multiple axes that I am plotting, this is what I use:<br />
<br /></div>
<pre>for a in ax:
a.set_axis_bgcolor('green')
a.xaxis.label.set_color('white')
a.yaxis.label.set_color('white')
a.spines['bottom'].set_color('white')
a.spines['top'].set_color('green')
a.spines['right'].set_color('green')
a.spines['left'].set_color('white')
a.tick_params(axis='x', colors='white')
a.tick_params(axis='y', colors='white')
</pre>
</div>
This will use white text and labels and set the background of the axis to green. Notice also the <code>savefig_kwargs={'facecolor':'green'}</code> section in the <code>ani.save</code> command which also is important.
<br />
<br />
Here are some of the results:<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_etFgnS-srDYolvrgTp283A6KtbEL9PiQr8HWlodL0kQLBZ3eT_VOqBmFIO5kgIAlXr_pPI4FZuxTvWIIrUUJr9wCgz9Vl227AoNA6aBoMO2-j21bwxO321qA-DtJYHr3XDf_05sUdvw/s1600/Screen+Shot+2014-03-15+at+12.51.22+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_etFgnS-srDYolvrgTp283A6KtbEL9PiQr8HWlodL0kQLBZ3eT_VOqBmFIO5kgIAlXr_pPI4FZuxTvWIIrUUJr9wCgz9Vl227AoNA6aBoMO2-j21bwxO321qA-DtJYHr3XDf_05sUdvw/s1600/Screen+Shot+2014-03-15+at+12.51.22+PM.png" height="320" width="200" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjj8mUnFGcjRUzpkTmcpLKD3ataGvPsgCmwSsi-aVL77PyfiwczEc9f-ab9yAHc_qLZIhwJ9U8SkmfPqE9o3lD8O4dkUhFHNYypGd8UBe_Gc9mPLNTlzX0GLWxXBQAqpwgB2-oCpVmKLYY/s1600/Screen+Shot+2014-03-15+at+12.51.33+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjj8mUnFGcjRUzpkTmcpLKD3ataGvPsgCmwSsi-aVL77PyfiwczEc9f-ab9yAHc_qLZIhwJ9U8SkmfPqE9o3lD8O4dkUhFHNYypGd8UBe_Gc9mPLNTlzX0GLWxXBQAqpwgB2-oCpVmKLYY/s1600/Screen+Shot+2014-03-15+at+12.51.33+PM.png" height="316" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Finally, I combine this all in Premiere or IMovie (although that can only handle one overlay and doesn't allow positioning), and get something like this:</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/89117769" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
Here are some of the scripts I used to generate this:<br />
<br />
<ul style="text-align: left;">
<li>https://gist.github.com/peabody124/9571409 - generates the altitude overlays</li>
<li>https://gist.github.com/peabody124/9571455 - generates the position overlays</li>
</ul>
<div>
<br /></div>
<h2 style="text-align: left;">
Next steps</h2>
<div>
<br /></div>
<div>
As is, this is a really powerful tool. However, what I think would be really awesome is to organize some scripts to generate a bunch of nice overlays, and then ideally write standalone python scripts that parse the log and spit out a video instead of going through IPython. The end goal would ideally be compiling to standalone applications, or alternatively integrating into the GCS and calling out to python (plausible?).</div>
<div>
<br /></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com1tag:blogger.com,1999:blog-1759046512792102553.post-40152391907742275432014-03-10T10:09:00.000-07:002014-03-10T10:20:33.556-07:00Microquad update<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
This is a followup on my <a href="http://buildandcrash.blogspot.com/2014/02/microquad-from-hovership-pro.html">previous post</a> about my foldable microquad from Hovership. I added a Mobius camera and 3DR radio so I could get telemetry. You can also see how I mounted the foam.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEinZhwh931zR_yjDvCWOcSPLunGrYGk8RyHEiQe1XU8vDWjFiKBmSalxTzZf40UAt1dSOGXZguFj1LbjkfBr338YVXpO59Y5wM0tuS4jHPf2ixLOowvPrDtRpsIPaLaBBVfZr4hg5fgwrA/s1600/IMG_20140226_184137.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEinZhwh931zR_yjDvCWOcSPLunGrYGk8RyHEiQe1XU8vDWjFiKBmSalxTzZf40UAt1dSOGXZguFj1LbjkfBr338YVXpO59Y5wM0tuS4jHPf2ixLOowvPrDtRpsIPaLaBBVfZr4hg5fgwrA/s1600/IMG_20140226_184137.jpg" height="240" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhT414sFTjTh5qgUMfrcPjrSgqsTZndF7mVdJvE9eba5FL-Bl0zHxaaNT7B3EiVM-uyahogNgx2CplPckAQ8bMDdQS-J5LqFEvPUOeA4CotZGdyKxhTouCzep_dV_2gNtvi5ElDV_MmXXo/s1600/IMG_20140226_184526.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhT414sFTjTh5qgUMfrcPjrSgqsTZndF7mVdJvE9eba5FL-Bl0zHxaaNT7B3EiVM-uyahogNgx2CplPckAQ8bMDdQS-J5LqFEvPUOeA4CotZGdyKxhTouCzep_dV_2gNtvi5ElDV_MmXXo/s1600/IMG_20140226_184526.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Probably not necessary, but I added some moon gel under the Mobius for a tad more vibration damping.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div style="text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhO_Lr5jEdy9E1S_EvYGMNo_Ok0EKkwHDTBV1JXP4m_8vtOcnyqWg8_LbMQi6LCeRMpFixn-fnxaTIYj7TAtlH_zlneKiJw7ZPkKQyW_av6tjCvmHlPFPVnZzriV5Lgf5gNB7uAHooG6X0/s1600/IMG_20140302_222458.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhO_Lr5jEdy9E1S_EvYGMNo_Ok0EKkwHDTBV1JXP4m_8vtOcnyqWg8_LbMQi6LCeRMpFixn-fnxaTIYj7TAtlH_zlneKiJw7ZPkKQyW_av6tjCvmHlPFPVnZzriV5Lgf5gNB7uAHooG6X0/s1600/IMG_20140302_222458.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlOYQqMsjW5xGLhT1WmoVrxOY_TquxXvH5Chfju7N1O4ZPk7tu2Bcz9lU0Ghxm5yMmyeeJkAVmt8e54Oxh6NJ2gAUkzJ8lh-1EWPfFsVK5xVmxUnFMu_wA_fc7CkP9q6QIcvHswPUfwd8/s1600/IMG_20140302_222556.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlOYQqMsjW5xGLhT1WmoVrxOY_TquxXvH5Chfju7N1O4ZPk7tu2Bcz9lU0Ghxm5yMmyeeJkAVmt8e54Oxh6NJ2gAUkzJ8lh-1EWPfFsVK5xVmxUnFMu_wA_fc7CkP9q6QIcvHswPUfwd8/s1600/IMG_20140302_222556.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Finally the arms are replaced with the latest version which lets them go on the right way up. Note the little channel for the wire so it doesn't add any strain.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgu2cX2_PCmsMfficJcb521IpH_bwvHu6w1aEBDH0Id6pyq0FF0KpOmo1610x-TO9uyKl4zbWxwTQPlfZxhHs7_phtt_FIa4QngFzOOOcUouvzvSxAwfST-EfkRMWu-cpjwgAAFEvQ0KKI/s1600/IMG_20140308_103556.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgu2cX2_PCmsMfficJcb521IpH_bwvHu6w1aEBDH0Id6pyq0FF0KpOmo1610x-TO9uyKl4zbWxwTQPlfZxhHs7_phtt_FIa4QngFzOOOcUouvzvSxAwfST-EfkRMWu-cpjwgAAFEvQ0KKI/s1600/IMG_20140308_103556.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h2 style="clear: both; text-align: left;">
Camping</h2>
<div>
I took it camping, and my friend had a nice camera and got some great shots of it in the air. I really like these.</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhGLRGlTZPq0VHCYezPikHWHaaP4KE0hmjRmnNm0Rqsthf9t32KpY46n6yuOzZG6D9mDo5tGIVmqNB80-yduDmO0bLMJKY_YQQI2qR6UG5B1yTt4EgdPwoGFp-iKYLJZRt8iONbeI9IHbw/s1600/12941579525_220c9edeba_h.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhGLRGlTZPq0VHCYezPikHWHaaP4KE0hmjRmnNm0Rqsthf9t32KpY46n6yuOzZG6D9mDo5tGIVmqNB80-yduDmO0bLMJKY_YQQI2qR6UG5B1yTt4EgdPwoGFp-iKYLJZRt8iONbeI9IHbw/s1600/12941579525_220c9edeba_h.jpg" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEilCGGa_8gRuykBMJsyjmTGO206EkVtgqGNfwrCkhPZR12bk-ykXQ8bxT3MBrV2cdXXtay6qnz4nFwOeawc9vDZpjZhpO6mW_zaVJqRExQteUD-iUOGwaz_YzQDlsg3FA7FHLmQNsR2Ot4/s1600/12941595145_f1d593479f_h.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEilCGGa_8gRuykBMJsyjmTGO206EkVtgqGNfwrCkhPZR12bk-ykXQ8bxT3MBrV2cdXXtay6qnz4nFwOeawc9vDZpjZhpO6mW_zaVJqRExQteUD-iUOGwaz_YzQDlsg3FA7FHLmQNsR2Ot4/s1600/12941595145_f1d593479f_h.jpg" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiS9FYdgeYiHsimWKN4C5e68ywvkJFuYbrVs7JxIKLl1aHlix5o9nNHm2xVPdZ107kW-Hckl0KHI5YmPF0J54Knd9h2hhcBP4yWPTzUb4xmCNC_Xxda4ydDdz1W6zyDNH9BA7YBm0VvwN4/s1600/12941604175_57c42238c9_h.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiS9FYdgeYiHsimWKN4C5e68ywvkJFuYbrVs7JxIKLl1aHlix5o9nNHm2xVPdZ107kW-Hckl0KHI5YmPF0J54Knd9h2hhcBP4yWPTzUb4xmCNC_Xxda4ydDdz1W6zyDNH9BA7YBm0VvwN4/s1600/12941604175_57c42238c9_h.jpg" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlJBgt_0tEtCohFqvplJthEY_K1EhqKLc24KzqyM2ZKuQAnjxl4gJfNN-zdF94BGZlCo7xLgIPTJN26dcaXEIUDXvWmsXhkYI3sTexlJvhAkKljMS5c4uBEhk1tvFD4UcEr0flnyK7Z9U/s1600/12941977424_04a1da64b2_h.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlJBgt_0tEtCohFqvplJthEY_K1EhqKLc24KzqyM2ZKuQAnjxl4gJfNN-zdF94BGZlCo7xLgIPTJN26dcaXEIUDXvWmsXhkYI3sTexlJvhAkKljMS5c4uBEhk1tvFD4UcEr0flnyK7Z9U/s1600/12941977424_04a1da64b2_h.jpg" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjRACrolVN45tqTF11hKIRZUwRiJHzni72-PWpyr-ZBfYxFiMzoKdfjEPVXa7aX6GJplCs4aiEHS4kbe3w1EXtkVI4W3ciyWMauaxLKKhesc0w8XyGpmOT4udlLrdqwR0Q-A7BYmI4qOwE/s1600/12941996904_17b2302145_h.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjRACrolVN45tqTF11hKIRZUwRiJHzni72-PWpyr-ZBfYxFiMzoKdfjEPVXa7aX6GJplCs4aiEHS4kbe3w1EXtkVI4W3ciyWMauaxLKKhesc0w8XyGpmOT4udlLrdqwR0Q-A7BYmI4qOwE/s1600/12941996904_17b2302145_h.jpg" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh4pH2jR5TYCVv9nyRTyY2xEX-wfjcdlWL5MfWE9ChP31P73KoOOhs9BtXsasf7cIF5l0l1VE4bhmwOyY_P3NrG6jQwHTYrJEGkHtzcOxiYe-J4hPQX0FqlxtldyAuHuuRM1R4lE8K6_CY/s1600/12942020264_c6704236e6_h.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh4pH2jR5TYCVv9nyRTyY2xEX-wfjcdlWL5MfWE9ChP31P73KoOOhs9BtXsasf7cIF5l0l1VE4bhmwOyY_P3NrG6jQwHTYrJEGkHtzcOxiYe-J4hPQX0FqlxtldyAuHuuRM1R4lE8K6_CY/s1600/12942020264_c6704236e6_h.jpg" height="212" width="320" /></a></div>
<div>
<br /></div>
The video from the mobius is pretty good.<br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/88023020" webkitallowfullscreen="" width="500"></iframe></div>
<div style="text-align: center;">
<br /></div>
<div style="text-align: center;">
<div style="text-align: left;">
All the video that is not stabilized was from the miniquad. It was quite windy on the top of that rock and I was super impressed with how it handled it. Then I was testing it out with our new code for altitude hold, and was that's even more impressive. I need to get some FPV gear on it to try out this mode better.</div>
</div>
<div style="text-align: center;">
<br /></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/88439963" webkitallowfullscreen="" width="500"></iframe></div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com6tag:blogger.com,1999:blog-1759046512792102553.post-77745414129250011272014-03-04T16:36:00.002-08:002014-03-04T16:36:26.212-08:00EEG and decoding<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
<div dir="ltr" style="text-align: left;" trbidi="on">
Following up on the EEG I <a href="http://buildandcrash.blogspot.com/2013/12/eeg-design-time-for-something-totally.html">designed</a> and <a href="http://buildandcrash.blogspot.com/2014/01/eeg-stuffing-and-testing.html">built</a>, I have been playing around with it somewhat to try and do some basic brain control work.<br />
<h2 style="text-align: left;">
EKG Testing</h2>
First I tested it as a basic EKG. I did this partly because it is a really strong signal and an easy check, and partly because i wanted to see how resistant to movement the system is. I was fairly pleased with the results. Even when I ran it produced a fairly robust signal and the heart rate was easily detectable. I was also pleased to see the 60 Hz level was fairly low in this situation, which is consistent with my theory that what I see is mostly RF pickup in the recording leads rather than a problem with the referencing.<br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/85627917" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<h2 style="text-align: left;">
EEG Electrodes positioning</h2>
So on to some basic brain activity classification. The first step was to reduce the noise, which means less hair.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhnR7Wnbfwy9AmVVkxnQKJZDhQL1nOGpc8wRk_u_dhCqAQKQ_ADA8ncsAf7I6zs8BMOvIQ-VBKGM-EIVUbn_Jr5gwfsSevP_yOr0piPAjU8BZvKutP5kVU6Rhuk0rdbSFPHYEwmxk-tJUY/s1600/IMG_20140304_070613.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhnR7Wnbfwy9AmVVkxnQKJZDhQL1nOGpc8wRk_u_dhCqAQKQ_ADA8ncsAf7I6zs8BMOvIQ-VBKGM-EIVUbn_Jr5gwfsSevP_yOr0piPAjU8BZvKutP5kVU6Rhuk0rdbSFPHYEwmxk-tJUY/s1600/IMG_20140304_070613.jpg" height="240" width="320" /></a></div>
<br />
I'm using <a href="http://www.neuro-source.com/product.php?id_product=544">AgCl electrodes now</a> (an improvement on my washers) recommended by <a href="http://www.openbci.com/forums/topic/check-out-my-hardware/page/3/#post-563">Chip</a>. Putting them on is a fairly annoying and messy affair, but only takes about 10 minutes.<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4vo51_pmRI6_MXnlatiF0IpFEzCGEZ-Xe2s5MWu3BRXtsvHnUQJ8MP5pLVcjRdbV1-mCF-GX1_vTzh3pTimJQB40Fo6ZpyxCQ4aPLysdJ28II8tII7feLZgDsCMDKMZl-ZeregsDatJU/s1600/IMG_20140304_071154.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4vo51_pmRI6_MXnlatiF0IpFEzCGEZ-Xe2s5MWu3BRXtsvHnUQJ8MP5pLVcjRdbV1-mCF-GX1_vTzh3pTimJQB40Fo6ZpyxCQ4aPLysdJ28II8tII7feLZgDsCMDKMZl-ZeregsDatJU/s1600/IMG_20140304_071154.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<span id="goog_1721948083"></span><span id="goog_1721948084"></span><br /></div>
<div style="text-align: center;">
<iframe allowfullscreen='allowfullscreen' webkitallowfullscreen='webkitallowfullscreen' mozallowfullscreen='mozallowfullscreen' width='320' height='266' src='https://www.blogger.com/video.g?token=AD6v5dzFInf-5A-HdWIL7uqoxotPqQ0jcG4dGWPPAfM1G-xP2iRJYlFS--XHXB0JKx64WDEv_qF0fc5SrhzZozr6' class='b-hbp-video b-uploaded' frameborder='0'></iframe></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgN0pKNUIhmQLpXJDbahT_a-ypuAUW6gXww6XTuQ_VMMADpBsm3lh23xItdvM9zu0M0Ar7-yEc_MUpZV3rlcwnJj0RN259Kb22x8L-p76ekWdM4SldwLFUp85HmKQbpGiYNveWah6PJvGw/s1600/IMG_20140304_072335.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgN0pKNUIhmQLpXJDbahT_a-ypuAUW6gXww6XTuQ_VMMADpBsm3lh23xItdvM9zu0M0Ar7-yEc_MUpZV3rlcwnJj0RN259Kb22x8L-p76ekWdM4SldwLFUp85HmKQbpGiYNveWah6PJvGw/s1600/IMG_20140304_072335.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
My electrode placement was as follows:<br />
<div style="text-align: left;">
</div>
<ul style="text-align: left;">
<li>Bias Black - right ear</li>
<li>Ch1 Light Gray - LV1</li>
<li>Ch2 Dark Gray - RV1</li>
<li>Ch3 White - left lower parietal</li>
<li>Ch4 Pink - right lower parietal</li>
<li>Ch5 Blue - left middle parietal</li>
<li>Ch6 Green - right middle parietal</li>
<li>Ch7 Yellow - left upper parietal</li>
<li>Ch8 Orange - right upper parietal</li>
<li>Ref Red - forehead</li>
</ul>
<div>
Using the impedance monitoring, I first saw that the occipital electrode impedances were high. This was easily fixed by adding more paste, and the monitoring confirmed the impedance was then normal. However, my upper parietal electrodes on both sides were also running fairly high. This was quite apparent when I walked to a part of my apartment with more electrical noise. Since these are obviously over the leg region, this was a problem. However, nothing another hairband from my girlfriend cannot fix.</div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi5AA3bcDuCGK-2h0f4n-dULzhyNKJVUuAWai75zMWkL0HmYV6M1ocFaFpnhwsHLbafH9tuQlo8kjyKc72abAkRaXybqN8fuWGTr6K35jhxTf4EuWqvrUiKF1ZON0oGFOkWXERH4XUwmS0/s1600/IMG_20140304_080604.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi5AA3bcDuCGK-2h0f4n-dULzhyNKJVUuAWai75zMWkL0HmYV6M1ocFaFpnhwsHLbafH9tuQlo8kjyKc72abAkRaXybqN8fuWGTr6K35jhxTf4EuWqvrUiKF1ZON0oGFOkWXERH4XUwmS0/s1600/IMG_20140304_080604.jpg" height="240" width="320" /></a></div>
<div>
<br />
In the long run, I'm definitely going to need something better to position the electrodes. I'm thinking it is time to drag out some old MRIs I got done during neuroscience experiments and <a href="http://buildandcrash.blogspot.com/2014/02/shapeoko-assembly-and-testing.html">use my CNC to build a solution</a>.<br />
<h2 style="text-align: left;">
Theta Waves</h2>
</div>
<div>
I have <a href="http://www.openbci.com/forums/topic/check-out-my-hardware/page/2/#post-544">previously shown</a> that with washers I can get a pretty nice modulation in the theta band from the occipital cortex when I close and open my eyes.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjV7BG0k3G8e-JmK3fps9IXavE6VadJyHLaONvCHSz8ynRQXa5RbEcG8CWy-CWVZMss7MgmoByEq5h3uwPjYUZy855rv_FPUc0cJoao1bIc8Q1pGjusXstn8iS51zYWgfHxyBxXzwy0Xas/s1600/wtQcciC.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjV7BG0k3G8e-JmK3fps9IXavE6VadJyHLaONvCHSz8ynRQXa5RbEcG8CWy-CWVZMss7MgmoByEq5h3uwPjYUZy855rv_FPUc0cJoao1bIc8Q1pGjusXstn8iS51zYWgfHxyBxXzwy0Xas/s1600/wtQcciC.png" height="320" width="270" /></a></div>
<h2 style="text-align: left;">
Brain control</h2>
<div>
To get the ball rolling with brain control, I wanted to see if I can classify real motion. This obviously has potential confounds of the motor activity directly modulating the EEG but let's ignore that for now. I wrote a stimulus for the android app that rotates through telling me to move my right arm, right leg, left arm and left leg. This produces a nice log file that automatically has this stimulus information synchronized to the EEG traces. I ran a shortly preliminary experiment and analyzed it, which was promising, so then I ran a longer 15 minute training session. Also for my own reference, this is the mapping from stimulus number to command:</div>
<div style="text-align: left;">
<ul style="text-align: left;">
<li>stim 2 - left arm</li>
<li>stim 3 - right arm</li>
<li>stim 4 - left leg</li>
<li>stim 5 - right leg</li>
</ul>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/88209271" webkitallowfullscreen="" width="500"></iframe> </div>
<div style="text-align: center;">
<br /></div>
<br />
<div>
For the analysis I extracted all of the two second segments for each stimulus and each channel and performed a welch spectral estimate. I then took the frequency bins between 1 and 30 Hz and concatenated those features together from all the channels to create a 240 dimensional feature vector for each trial. This processing of the log files was just done using the nice <a href="https://github.com/TauLabs/TauLabs/pull/1108">python parsing framework</a> we just merged into <a href="http://taulabs.org/">Tau Labs</a>. I then saved the parsed data in a matlab structure since I'm more comfortable doing the machine learning there (although hopefully I'll get there with SciPy and Python).</div>
<div>
<br /></div>
<div>
A first pass glance at the average response in each of the four conditions shows what appears to be a difference, although of course this lacks any statistics.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiYLnGVlHTKrf1ptsP5pVHkGSir-3IwpQPHD1qh-IXwZ3F5ejPQD5QMdYbL0EEgu3RoZkZQKNNY_paK4UiHenx54seb-kXiQJGGEaYsrbRWjAt6J8DVlQpy4RO0UCv_3Lkg5pnE5uiLm9A/s1600/Screen+Shot+2014-03-04+at+10.22.45+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiYLnGVlHTKrf1ptsP5pVHkGSir-3IwpQPHD1qh-IXwZ3F5ejPQD5QMdYbL0EEgu3RoZkZQKNNY_paK4UiHenx54seb-kXiQJGGEaYsrbRWjAt6J8DVlQpy4RO0UCv_3Lkg5pnE5uiLm9A/s1600/Screen+Shot+2014-03-04+at+10.22.45+AM.png" height="136" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div>
<br /></div>
<div>
Since I didn't run tons of trials, I wanted to reduce the dimensionality a little bit for the classifier, so picked the three frequency peaks from all the channels to feed into the classifier. This reduced things to a 24 dimensional space.</div>
<div>
<br /></div>
<div>
I used <a href="http://arxiv.org/pdf/1310.5438v1">variational bayesian logistic regression</a> which I used in some of my thesis work and seems to work quite well for building well regularized classifiers. I would collect all the trials from two stimuli, and using leave-one-out cross validation measured how well I could classify the EEG feature vectors by the stimuli shown.<br />
<br />
This is the performance of the classifier with 267 trials for all the pairwise comparisons:</div>
<div>
<br /></div>
</div>
<table border="1" style="width: 300px;">
<tbody>
<tr> <td></td> <th>RA</th> <th>LL</th> <th>RL</th> </tr>
<tr> <th>LA</th> <td>0.5469</td> <td>0.5386</td> <td>0.5625</td> </tr>
<tr> <th>RA</th> <td>0</td> <td>0.5381</td> <td>0.4766</td> </tr>
<tr> <th>LL</th> <td>0</td> <td>0</td> <td>0.6394</td> </tr>
</tbody>
</table>
<br />
Which shows the average performance is around 0.55. This is better than chance, but not anywhere near as good as I would like. Interesting, the performance on my preliminary analysis was better:<br />
<br /></div>
<table border="1" style="width: 300px;">
<tbody>
<tr> <td></td> <th>RA</th> <th>LL</th> <th>RL</th> </tr>
<tr><th>LA</th><td>0.3333</td> <td>0.6111</td> <td>0.7222</td> </tr>
<tr><th>RA</th><td>0</td> <td>0.5278</td> <td>0.7500</td> </tr>
<tr><th>LL</th><td>0</td> <td>0</td> <td>0.5278</td> </tr>
</tbody></table>
<br />
<div>
Although one condition was doing poorly, most of them were doing better. This is despite having many less trials. My guess in this case is that electrode placement played a role and I wasn't properly over the motor cortex in this recent attempt. Also I think my upper parietal electrodes were a bit low. Not putting the occipital electrodes improved the performance on the larger experiment, most likely by reducing overfitting.</div>
<br />
<table border="1" style="width: 300px;">
<tbody>
<tr> <td></td> <th>RA</th> <th>LL</th> <th>RL</th> </tr>
<tr> <th>LA</th> <td>0.5469</td> <td>0.6475</td> <td>0.5781</td> </tr>
<tr> <th>RA</th> <td>0</td> <td>0.6304</td> <td>0.5000</td> </tr>
<tr> <th>LL</th> <td>0</td> <td>0</td> <td>0.7003</td> </tr>
</tbody></table>
<br />
<div style="text-align: left;">
This brought the average to 0.6. However, this is still not enough to be flying with.</div>
<h2 style="text-align: left;">
Going forward</h2>
</div>
<div dir="ltr" style="text-align: left;" trbidi="on">
<ul style="text-align: left;">
<li>I think I'll try putting all the electrodes over the parietal or motor cortex and not bother with an occipital electrodes.</li>
<li>Longer training session as well as using one second stimulus presentations to try and get the trial numbers up. </li>
<li>Different classifiers. From what I have seen from the number of included features, there is not enough regularization.</li>
<li>Run classifier continuously on data rather than on individual trials</li>
<li>Once that is working, write some online visualization of the classifier output</li>
</ul>
</div>
</div>
</div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com1tag:blogger.com,1999:blog-1759046512792102553.post-57788904703563007322014-02-23T19:08:00.001-08:002014-03-10T15:30:15.018-07:00Microquad from hovership pro<div dir="ltr" style="text-align: left;" trbidi="on">
<div class="separator" style="clear: both; text-align: left;">
<b>Update:</b> see <a href="http://buildandcrash.blogspot.com/2014/03/microquad-update.html">this post</a> for the latest with this frame. See the <a href="http://www.thingiverse.com/thing:251002">entry on thingverse</a> to make your own.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhmvl5HZ-kDaYB0JMDsn5KoSg0C-Vrf3zVBmuWjUW0j6AIrP-FHtWsSsTOXsU8JQivVOO-JSfLuFxPIYXweBbROjbsSrFOVz8MKrbfJZJ18kmTLbdjwj_-agjH3F5LkFQPHY6g3qPPO3YU/s1600/DSC02135.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhmvl5HZ-kDaYB0JMDsn5KoSg0C-Vrf3zVBmuWjUW0j6AIrP-FHtWsSsTOXsU8JQivVOO-JSfLuFxPIYXweBbROjbsSrFOVz8MKrbfJZJ18kmTLbdjwj_-agjH3F5LkFQPHY6g3qPPO3YU/s1600/DSC02135.JPG" height="351" width="400" /></a></div>
<br />
<br />
Steve (aka hovership) was nice enough to send me one of his <a href="http://www.hovership.com/2014/02/07/3d-printable-folding-micro-fpv-h-quadcopter/">3D printed foldable microquads</a>, which I'm really excited about. It's nice and small and even has an offset mounting hole for Sparky which is pretty awesome. It is designed for FPV, although I haven't got it set up for that yet. So far it is a ton of fun for normal flying.<br />
<br />
For electronics I'm using:<br />
<br />
<ul style="text-align: left;">
<li><a href="http://buildandcrash.blogspot.com/2013/05/sparky-testing-and-building-no-crashing.html">Sparky</a> flight controller</li>
<li>Motors: <a href="http://www.google.com/url?q=http%3A%2F%2Fwww.myrcmart.com%2Fzmr-1804-2400kv-micro-outrunner-brushless-motor-clockwise-p-6281.html&sa=D&sntz=1&usg=AFQjCNHqJszLWSIOwDA8vXKMbUHQQpKAyg">leftward</a> and <a href="http://www.google.com/url?q=http%3A%2F%2Fwww.myrcmart.com%2Frcx-1804-2400kv-micro-outrunner-brushless-motor-anticlockwise-p-6280.html&sa=D&sntz=1&usg=AFQjCNFXzH6q1chDPLLuW0TAAckqWMLKTg">rightward</a> nuts</li>
<li>ESCs: AfroESC 12A</li>
</ul>
<br />
<h2 style="text-align: left;">
Construction</h2>
I took some photos to document the construction.<br />
<br />
<table align="center" cellpadding="5" cellspacing="1"><tbody>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhhOrpVQ8JqbN1lVZFduMKR6zNgwfGlc44m6a3XQje1ebgDFt0X8-4TxcJPBGs4j0DIeWFWzrjDrQM1OHZhwcPJGM7wvL3UlVnGlvDUy0qQ2lBfIUL4O1efwwEeh9e_tFpU0FTNY6wjAk4/s1600/DSC02122.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhhOrpVQ8JqbN1lVZFduMKR6zNgwfGlc44m6a3XQje1ebgDFt0X8-4TxcJPBGs4j0DIeWFWzrjDrQM1OHZhwcPJGM7wvL3UlVnGlvDUy0qQ2lBfIUL4O1efwwEeh9e_tFpU0FTNY6wjAk4/s1600/DSC02122.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhwrfto9OJAbdXPkKWrMPL1dnTHZeV37V0udO2moY-IVea6UBAThEr4coNPrzWvUmWIp98SldkdP_D1gzzGx9bBtp-rr8JkBcweAymTl1G_oDMOqJUYpFbp-nu9wgaZAU3yzK0-oIbwiss/s1600/IMG_20140221_172354.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhwrfto9OJAbdXPkKWrMPL1dnTHZeV37V0udO2moY-IVea6UBAThEr4coNPrzWvUmWIp98SldkdP_D1gzzGx9bBtp-rr8JkBcweAymTl1G_oDMOqJUYpFbp-nu9wgaZAU3yzK0-oIbwiss/s1600/IMG_20140221_172354.jpg" height="150" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiReI1Xm1YxW4OOrp5fRsfGhOzOwqcjG9_OOVEuxm1CI4jy3Vqq_DvtuoZAHUBl5D4vx5UZSf826kSrVObtW3k9oIrR9spLpzqiPMZjHT7lEcY1HX-cz7paLTCBH7h03FGrvcATJYT7oqg/s1600/IMG_20140221_172743.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiReI1Xm1YxW4OOrp5fRsfGhOzOwqcjG9_OOVEuxm1CI4jy3Vqq_DvtuoZAHUBl5D4vx5UZSf826kSrVObtW3k9oIrR9spLpzqiPMZjHT7lEcY1HX-cz7paLTCBH7h03FGrvcATJYT7oqg/s1600/IMG_20140221_172743.jpg" height="150" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgen7vJ9nJioXncHCLZzPyjVL85GvTIQsZKXjSpUnasLt0TvHnciONhshvdmlMm9OVuJONmBo5ipz7p1UNxEVDYk9VpCsqojr8yyNXVzlmaDiftsi6YWCEk9mU69I0N8ZIAYWWI_XBht2w/s1600/IMG_20140221_172924.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgen7vJ9nJioXncHCLZzPyjVL85GvTIQsZKXjSpUnasLt0TvHnciONhshvdmlMm9OVuJONmBo5ipz7p1UNxEVDYk9VpCsqojr8yyNXVzlmaDiftsi6YWCEk9mU69I0N8ZIAYWWI_XBht2w/s1600/IMG_20140221_172924.jpg" height="150" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhrcRcEZjDjkDytzrtfOKaeot5LFKyGI6ZNNeODV16dH3NL8l-LZgIjIb3HYPo4cBERBD3sPDB-pdcsVLiv3MLnsx16KfdoV0gY3-9e7VINlzBvAcqcm20IfPCiu5Avp-hTzwsZlUE2HPQ/s1600/IMG_20140221_172354.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhrcRcEZjDjkDytzrtfOKaeot5LFKyGI6ZNNeODV16dH3NL8l-LZgIjIb3HYPo4cBERBD3sPDB-pdcsVLiv3MLnsx16KfdoV0gY3-9e7VINlzBvAcqcm20IfPCiu5Avp-hTzwsZlUE2HPQ/s1600/IMG_20140221_172354.jpg" height="150" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEheLWPSBxNqCt-YxwW946QPQNXnFBQQIlOvSy9OyU39lMrNPI0-nvHv2prf3S_OmQsxkKwfz22TT6Nm898hLzc7KVhVQfxTnvW3F3ki3xyajeEFzVga2rG49cqtoDBZmrhHpuVs_GkpsFg/s1600/IMG_20140221_172743.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEheLWPSBxNqCt-YxwW946QPQNXnFBQQIlOvSy9OyU39lMrNPI0-nvHv2prf3S_OmQsxkKwfz22TT6Nm898hLzc7KVhVQfxTnvW3F3ki3xyajeEFzVga2rG49cqtoDBZmrhHpuVs_GkpsFg/s1600/IMG_20140221_172743.jpg" height="150" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEivWieSQ8UDk0eBi2lX082EKFOPKzX_iLNSAK8fPhg2zfD_Sa26nRl4mqfYlzgMnkh4aN2f-clzGg0AZHutmo8jx1m8INjz2xYRPxc8m05U-QVPJRKh1yQOv8vjyo1PddK0hgKniYjh_FY/s1600/IMG_20140221_172822.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEivWieSQ8UDk0eBi2lX082EKFOPKzX_iLNSAK8fPhg2zfD_Sa26nRl4mqfYlzgMnkh4aN2f-clzGg0AZHutmo8jx1m8INjz2xYRPxc8m05U-QVPJRKh1yQOv8vjyo1PddK0hgKniYjh_FY/s1600/IMG_20140221_172822.jpg" height="150" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhDboahUD9bZFF2yJxyQsoeuwgcAFsDQrhky4HQ0gKlH2ONC2797-W9eCxArongRD_AdgadYP99L3MzDcwWTZSczWOZxnS1sza5_5wuaLeBowQn2p2Ea4Q5kjANHwLAVF0p-OsblT3eDiU/s1600/DSC02123.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhDboahUD9bZFF2yJxyQsoeuwgcAFsDQrhky4HQ0gKlH2ONC2797-W9eCxArongRD_AdgadYP99L3MzDcwWTZSczWOZxnS1sza5_5wuaLeBowQn2p2Ea4Q5kjANHwLAVF0p-OsblT3eDiU/s1600/DSC02123.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4UhFGXM_-qT4XVf3GKt8sL0UaHwaqvrmp81QkJM4p9ozp2glIk0Kn_ZSZN494estg3mZVtqi8J5BZjs6CzP2CjXDTaPVpJgizWklsq4uMEfwcYKUvOG_Z6_1WkueYN6zqftQIi5_GjU0/s1600/DSC02124.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi4UhFGXM_-qT4XVf3GKt8sL0UaHwaqvrmp81QkJM4p9ozp2glIk0Kn_ZSZN494estg3mZVtqi8J5BZjs6CzP2CjXDTaPVpJgizWklsq4uMEfwcYKUvOG_Z6_1WkueYN6zqftQIi5_GjU0/s1600/DSC02124.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgEFc9f9CCF0CvCS61phcB6rPkuXOfWncLyexQx3E6YsxKSBATUZZLYcq3Lspdee5LiSVL4fE3u5udiASqYms3OQR9k7SUoFIrYRB8ZGho5B8EPfddJaGkK_otLwCxnexaI-1yE1chHGrk/s1600/DSC02125.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgEFc9f9CCF0CvCS61phcB6rPkuXOfWncLyexQx3E6YsxKSBATUZZLYcq3Lspdee5LiSVL4fE3u5udiASqYms3OQR9k7SUoFIrYRB8ZGho5B8EPfddJaGkK_otLwCxnexaI-1yE1chHGrk/s1600/DSC02125.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiG4lQ9y3qK1NXMtWme93uC9mM6r5Qq6QM_KpH859vkEB_bmNv9u_wpPyms3S7pUbrulCh5T3qBXUFxANc6S3xoZ-fLOpBi0nImoHq9Q8f81uwvlxSPleFvBer_PRATuAItTDUFpSX1WdA/s1600/DSC02126.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiG4lQ9y3qK1NXMtWme93uC9mM6r5Qq6QM_KpH859vkEB_bmNv9u_wpPyms3S7pUbrulCh5T3qBXUFxANc6S3xoZ-fLOpBi0nImoHq9Q8f81uwvlxSPleFvBer_PRATuAItTDUFpSX1WdA/s1600/DSC02126.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjN1dXtSJUmHtV6sNvxO2C2yjhIwNcuBg4roaPQ-pz5Q2E6tEt4j5VV6oKbPt68yd0iLVczukXFcG9g1VbY5jVG3zSCDqHISyrDQFfEJrgeWuF5PudzCMkxbqEgUiSXnGQgWfTSzhp32-I/s1600/DSC02127.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjN1dXtSJUmHtV6sNvxO2C2yjhIwNcuBg4roaPQ-pz5Q2E6tEt4j5VV6oKbPt68yd0iLVczukXFcG9g1VbY5jVG3zSCDqHISyrDQFfEJrgeWuF5PudzCMkxbqEgUiSXnGQgWfTSzhp32-I/s1600/DSC02127.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhrN_u9ZK0xjQOIGkdlK-5gqGVC2GSFsrAFDY7L2e2-ZWKQNVNAGzBUwUygbg-ZzCpmdk3klE33VKnyXN8ELtutuE6u0yIVySW4prw9J3zFgJaOzPJHI89-PGBKzaO18P1kI7NDMIP0ISU/s1600/DSC02128.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhrN_u9ZK0xjQOIGkdlK-5gqGVC2GSFsrAFDY7L2e2-ZWKQNVNAGzBUwUygbg-ZzCpmdk3klE33VKnyXN8ELtutuE6u0yIVySW4prw9J3zFgJaOzPJHI89-PGBKzaO18P1kI7NDMIP0ISU/s1600/DSC02128.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2lA5bHz4JKooYYw86JSAbt7f1P3V-d93KJqCSwRPPNxQzmsxuM5uaexgSruWn7T7_ynrzertXAjJ3XD1g3EbvyvSPOKH8WAYFYJ8UvYY_S_KXRZF2f8J6NtIyFhl5rbY0vHb6lD1A6AI/s1600/DSC02129.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj2lA5bHz4JKooYYw86JSAbt7f1P3V-d93KJqCSwRPPNxQzmsxuM5uaexgSruWn7T7_ynrzertXAjJ3XD1g3EbvyvSPOKH8WAYFYJ8UvYY_S_KXRZF2f8J6NtIyFhl5rbY0vHb6lD1A6AI/s1600/DSC02129.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhpYxTnkTrfEjAJXHM6TIufdMUQhfEfwy91mvTJ7Xw9BncnK2gAbaWMKVCep4QFV7vYyZnOVPewovE-uk8yDE_unnDUwnql3NTImQzdeWOSrZoSofa6GMcVycYX80TcbZGSEU3r9QSl_58/s1600/DSC02130.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhpYxTnkTrfEjAJXHM6TIufdMUQhfEfwy91mvTJ7Xw9BncnK2gAbaWMKVCep4QFV7vYyZnOVPewovE-uk8yDE_unnDUwnql3NTImQzdeWOSrZoSofa6GMcVycYX80TcbZGSEU3r9QSl_58/s1600/DSC02130.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjz-ESvSm87K_MH6W6nc930JWo7rUwCF6LjN9OWmJj45jK7awAA3LOt-idZsqefNlHn6GR6D7VRnAtn4B2paDiSU2lOkzyY8aKF2WiVwtPNy_qZCHJIjjxvUOB4JhI-CnFphu1txciYNFQ/s1600/DSC02131.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjz-ESvSm87K_MH6W6nc930JWo7rUwCF6LjN9OWmJj45jK7awAA3LOt-idZsqefNlHn6GR6D7VRnAtn4B2paDiSU2lOkzyY8aKF2WiVwtPNy_qZCHJIjjxvUOB4JhI-CnFphu1txciYNFQ/s1600/DSC02131.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEioY5LOXcgyNhOByx-MR3ci_7uDhf6gulvLaPRIw962iOfEKNPc5toJhOdUzwPvRAkU41PqVbCUBlfz2t55Z7sWIxYZfZuwngkf4V9cBif0uM4DGjYbAGF1l7-5duFrNuqmMAalzMpZmF0/s1600/DSC02132.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEioY5LOXcgyNhOByx-MR3ci_7uDhf6gulvLaPRIw962iOfEKNPc5toJhOdUzwPvRAkU41PqVbCUBlfz2t55Z7sWIxYZfZuwngkf4V9cBif0uM4DGjYbAGF1l7-5duFrNuqmMAalzMpZmF0/s1600/DSC02132.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi6jDWD-1WubSqGLnopVN_VlorAgObt7NlVOiKQcqectXd-ECBeTqknNgwmk1BtBlDlmlg3Gvpm0v13ndzbAK6Z2_5IpT_LBby_QMtSL93MvtsayjGQ_wnWCJIbBSfRi8K5_DOII9mTSVE/s1600/DSC02134.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi6jDWD-1WubSqGLnopVN_VlorAgObt7NlVOiKQcqectXd-ECBeTqknNgwmk1BtBlDlmlg3Gvpm0v13ndzbAK6Z2_5IpT_LBby_QMtSL93MvtsayjGQ_wnWCJIbBSfRi8K5_DOII9mTSVE/s1600/DSC02134.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiDO3pQ3gJ2ZaMIsv29v6EC2GMikT9V9CILn0QkWVM1FiEL3BJ3dVqPHMpqb8xFI65BIXdIhKHMPnOBIrCUUxLtvEecC_UQWrfqyMbTf1icXheL7PtO1Hf_Z9GLwbusB8Gp4y1yVZGqVBE/s1600/DSC02135.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiDO3pQ3gJ2ZaMIsv29v6EC2GMikT9V9CILn0QkWVM1FiEL3BJ3dVqPHMpqb8xFI65BIXdIhKHMPnOBIrCUUxLtvEecC_UQWrfqyMbTf1icXheL7PtO1Hf_Z9GLwbusB8Gp4y1yVZGqVBE/s1600/DSC02135.JPG" height="132" width="200" /></a></td>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhbVfPg9vVqU0yPslqzLaU8o-dAKpg6efVsmqzenhdRLXwt49VU6cs45Tgk3fplCa2VsOXMS6ly0HIWkVOxvo06ondYcLTnJMKjcI0ADimegXpBFpBnUtfxjGtumZqePxZ2ljmHQz-BaNU/s1600/DSC02137.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhbVfPg9vVqU0yPslqzLaU8o-dAKpg6efVsmqzenhdRLXwt49VU6cs45Tgk3fplCa2VsOXMS6ly0HIWkVOxvo06ondYcLTnJMKjcI0ADimegXpBFpBnUtfxjGtumZqePxZ2ljmHQz-BaNU/s1600/DSC02137.JPG" height="132" width="200" /></a></td>
</tr>
<tr>
<td><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhbKG_edPXzqSsy3XY05Vs7rQT_g2NXOqTwkJM9X168ToNpoDPkS9Bmqntkyv4UUgVbxjpxan3VZhfQlq45Zpy1cqkRIx7BpqvIr5pdUaNKk1A_TnrYBKMw3ip9UE_AjtSVU8_EpCn9zgs/s1600/DSC02139.JPG" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhbKG_edPXzqSsy3XY05Vs7rQT_g2NXOqTwkJM9X168ToNpoDPkS9Bmqntkyv4UUgVbxjpxan3VZhfQlq45Zpy1cqkRIx7BpqvIr5pdUaNKk1A_TnrYBKMw3ip9UE_AjtSVU8_EpCn9zgs/s1600/DSC02139.JPG" height="132" width="200" /></a></td>
</tr>
</tbody></table>
<br />
I like how the single sided low profile of Sparky works well with getting it nice and small.<br />
<h2 style="text-align: left;">
Configuration</h2>
<div>
<div style="text-align: center;">
<div style="text-align: justify;">
<span style="text-align: left;">I configured it for basic flight the way described in this video.</span></div>
</div>
<div style="text-align: center;">
<span style="text-align: left;"><br /></span></div>
</div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/86279413" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
The tuning values that worked well were:<br />
<br />
<br />
I wanted this quad to be really well calibrated for optimal navigation. I went ahead and ran the complete temperature and 6 point calibration, as well as using an advanced feature for autotuning that lets you adjust the aggressiveness of the tuning. Here is a video that describes the process:<br />
<br />
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/87430180" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
The tuning values I ended up with were:<br />
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGEzdfteHdQGf9TDfazsTzgXpMO1Wgkf5f1CbC2Bq7jFHLg2OT3HXQiW9PqaD44mHy7JVymqqWrvnwsXZy_LSSKAnb1BeShiAfLbUYqZWg6Vose07FHpwQsKAYwmPkLQUCeYUs-hI6ZPI/s1600/Screen+Shot+2014-02-22+at+5.48.45+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjGEzdfteHdQGf9TDfazsTzgXpMO1Wgkf5f1CbC2Bq7jFHLg2OT3HXQiW9PqaD44mHy7JVymqqWrvnwsXZy_LSSKAnb1BeShiAfLbUYqZWg6Vose07FHpwQsKAYwmPkLQUCeYUs-hI6ZPI/s1600/Screen+Shot+2014-02-22+at+5.48.45+PM.png" height="262" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<h2 style="text-align: left;">
Flying</h2>
<div>
I wanted to have more time to really take it out and tear around, but time is limited. So far I really like how it flies. It's quite locked in and snappy and has probably 7-8 minutes with 3S 800mAh batteries. I've given it some fairly heavy landings and the landing gear is holding up well. No majors crashes although some small flying into things. It also can carry a GoPro which will make it a nice easy traveler for taking quick videos. Looks like 3D printed quads are going to be big this year.</div>
<div>
<br /></div>
<div>
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/87433569" webkitallowfullscreen="" width="500"></iframe> </div>
<br />
<br />
Coming up (hopefully), will be a video about tuning up the quad for the best navigation and RTH. I've already got some improvements to altitude control in the pipeline from playing with this.<br />
<br />
<br /></div>
Anonymoushttp://www.blogger.com/profile/08527686472814719432noreply@blogger.com2tag:blogger.com,1999:blog-1759046512792102553.post-17746726448506710362014-02-22T14:56:00.001-08:002014-02-22T14:56:23.759-08:00Shapeoko assembly and testing<div dir="ltr" style="text-align: left;" trbidi="on">
I received my <a href="https://www.inventables.com/technologies/desktop-cnc-mill-kit-shapeoko-2">Shapeoko</a> last week which was extremely exciting. I ordered the full kit which (as the name implies) comes with everything you need to get started. Well, except for a jumper that is not documented (see below).<br />
<br />
There are lots of little upgrades that you might want to look at still - the new baseboard and bumper switches being high on my list to get. It uses an Arduino for control (which despite 15+ years playing with embedded stuff I'd managed to avoid till now). I was really really really tempted to not get the electrical kit and make my own controller (after all it could basically use the software and hardware from <a href="http://buildandcrash.blogspot.com/2013/05/sparky-brushless-gimbal-controller.html">Sparky BGC</a> and/or my <a href="http://buildandcrash.blogspot.com/2011/11/esc-development.html">ESC</a>) however I really want this to be a tool rather than a project in itself so sucked i up.<br />
<br />
Of course I had to immediately start assembling, so that shot two nights of studying, but oh well. I snapped a few photos along the way.<br />
<br />
<h3 style="text-align: left;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgvPNh-xJA1m4GvRxsSxSY9bh4A-XpSFd7v3Qtq2qxQptbdd7K4-3YbIgiH25Vr0ebnrGG5GMu_Hv4DkDdxBNRiT0fSWfMopDLhqSwmZLydXgvae497qZNkQW1wmiDU0uK0eooZK5_AMww/s1600/IMG_20140213_193757.jpg" imageanchor="1" style="clear: left; float: left; margin-bottom: 1em; margin-right: 1em;"><br /></a></h3>
<h2 style="text-align: left;">
Assembly</h2>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgvPNh-xJA1m4GvRxsSxSY9bh4A-XpSFd7v3Qtq2qxQptbdd7K4-3YbIgiH25Vr0ebnrGG5GMu_Hv4DkDdxBNRiT0fSWfMopDLhqSwmZLydXgvae497qZNkQW1wmiDU0uK0eooZK5_AMww/s1600/IMG_20140213_193757.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgvPNh-xJA1m4GvRxsSxSY9bh4A-XpSFd7v3Qtq2qxQptbdd7K4-3YbIgiH25Vr0ebnrGG5GMu_Hv4DkDdxBNRiT0fSWfMopDLhqSwmZLydXgvae497qZNkQW1wmiDU0uK0eooZK5_AMww/s1600/IMG_20140213_193757.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgWnF87oSEQR2fQ41UUrg9i4zZAy2E0GGGhxQibERus-4U24bQ51YW9O0Ri7iGZWxJW1MqTEMIQt4m8IhDIa_im8hMPIZtqcROUDmer623ckwulnjp8mGBEFY_LVWaNS0xlp3zPAizBVDo/s1600/IMG_20140213_201532.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgWnF87oSEQR2fQ41UUrg9i4zZAy2E0GGGhxQibERus-4U24bQ51YW9O0Ri7iGZWxJW1MqTEMIQt4m8IhDIa_im8hMPIZtqcROUDmer623ckwulnjp8mGBEFY_LVWaNS0xlp3zPAizBVDo/s1600/IMG_20140213_201532.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Stuffing all the bearings into these took forever and killed my fingers</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj9k-1AFUytn-tDGaRisnegWQIIbjyjaWy3-HRG6Cuhqk41QOPZX2Dzg81pNsZgg1F2-UmO5rgWum3TidJJ18gWMi8wo-cEbuQpPI8a2OdvO9q_VLD3TENVVfk84atvSooST7siSAHAjCI/s1600/IMG_20140213_212025.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj9k-1AFUytn-tDGaRisnegWQIIbjyjaWy3-HRG6Cuhqk41QOPZX2Dzg81pNsZgg1F2-UmO5rgWum3TidJJ18gWMi8wo-cEbuQpPI8a2OdvO9q_VLD3TENVVfk84atvSooST7siSAHAjCI/s1600/IMG_20140213_212025.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">This gives a little spring to the z-axis in case of a crash</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgCxAk0Lsxa12wivmA0xzVxcdG8Q72c8O9JJXbMC1lRvd7_TWZSkjd62F4gHYTxvieKVnZW2hgCPEEq-xg6vpfdoVV_Bb8PpZrHBBbMdluxg1sFymqdy-y8cvL6psOs2mUrsZ4WM1JRFAU/s1600/IMG_20140213_204441.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgCxAk0Lsxa12wivmA0xzVxcdG8Q72c8O9JJXbMC1lRvd7_TWZSkjd62F4gHYTxvieKVnZW2hgCPEEq-xg6vpfdoVV_Bb8PpZrHBBbMdluxg1sFymqdy-y8cvL6psOs2mUrsZ4WM1JRFAU/s1600/IMG_20140213_204441.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">The rollers for all the axes. I didn't notice at this point you should add the screw terminals if you want them. I figured I would solder but they were ultimately easier so I had to get them on later. Oh well.</td></tr>
</tbody></table>
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgCxAk0Lsxa12wivmA0xzVxcdG8Q72c8O9JJXbMC1lRvd7_TWZSkjd62F4gHYTxvieKVnZW2hgCPEEq-xg6vpfdoVV_Bb8PpZrHBBbMdluxg1sFymqdy-y8cvL6psOs2mUrsZ4WM1JRFAU/s1600/IMG_20140213_204441.jpg" imageanchor="1" style="clear: left; float: left; margin-bottom: 1em; margin-right: 1em;"><br /></a>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiWLZfW3DJBA3orfcVZ2oJg07BvDgBV1xmyrXZZg-S2eiF-iG-XEy-YBlJfbLqL_yTbq-J6UmiQPbR_3wNgKPY8Iew8s2B4m6b_guonOSuBxwfvf3crJKvC5MGQ3TWA8nww79ajxJW7l_Y/s1600/IMG_20140213_223215.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiWLZfW3DJBA3orfcVZ2oJg07BvDgBV1xmyrXZZg-S2eiF-iG-XEy-YBlJfbLqL_yTbq-J6UmiQPbR_3wNgKPY8Iew8s2B4m6b_guonOSuBxwfvf3crJKvC5MGQ3TWA8nww79ajxJW7l_Y/s1600/IMG_20140213_223215.jpg" height="320" width="240" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Finished X and Z axis</td></tr>
</tbody></table>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh59BNpudlyygtKz1sqXPrm92iqh91Ls2X4Cek-sxIzJbfifDzZGh8DM7yF6wO-7DzCFHSU1gkcNBcpErgfJKmKDlYBZLn0WQ6R6dFwBcmTEQBCV57YnI5jNUSLuBdW7G1k0WG7B4bUaRY/s1600/1392355396367.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEh59BNpudlyygtKz1sqXPrm92iqh91Ls2X4Cek-sxIzJbfifDzZGh8DM7yF6wO-7DzCFHSU1gkcNBcpErgfJKmKDlYBZLn0WQ6R6dFwBcmTEQBCV57YnI5jNUSLuBdW7G1k0WG7B4bUaRY/s1600/1392355396367.jpg" height="305" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">End of night 1. Almost there - just the last mounts (which involved lots of tapping holes) and then on to electronics.</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: center;">
</div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhPgU_vOGyi8PBgmfe9LzcIirmyiaCS2keaUHp5gHmNvh1hERfJAKYIP1GgxhIbLjEmYyz3MHLDImP6-ZVB6tZZNJVnx97cKJnwEfaPk1V0f625aQnsf6IEvDIXKJVwkbkBDjkffzyJEaU/s1600/IMG_20140216_233537.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhPgU_vOGyi8PBgmfe9LzcIirmyiaCS2keaUHp5gHmNvh1hERfJAKYIP1GgxhIbLjEmYyz3MHLDImP6-ZVB6tZZNJVnx97cKJnwEfaPk1V0f625aQnsf6IEvDIXKJVwkbkBDjkffzyJEaU/s1600/IMG_20140216_233537.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">And all finished!</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgz0TcOfoYt5p8OcR25WwVvx7bDpLKA4u1NYOxJlT53lmeg720_Pilc1nTDwubDRakPu0lIpbEPZaQBjkBEc00QbZQ5UYVZurimJS3_BZrftUrxXPUeTuqyIoKL_bzStGg3RG_LkKaC7iM/s1600/IMG_20140216_233550.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgz0TcOfoYt5p8OcR25WwVvx7bDpLKA4u1NYOxJlT53lmeg720_Pilc1nTDwubDRakPu0lIpbEPZaQBjkBEc00QbZQ5UYVZurimJS3_BZrftUrxXPUeTuqyIoKL_bzStGg3RG_LkKaC7iM/s1600/IMG_20140216_233550.jpg" height="240" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
I did print a "Hello world" but it looks fairly ugly because of sloppy pen mounting so I will not show it :).</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
One thing to look out for though, is there is an error in the documentation unless I missed something. For grblShield it says to use $2=320 but the issue with this is that it assumes 2x microstepping on the z-axis. The way the grblShield comes configured, it is set for 8x microstepping. If you follow the instructions as written, your z-axis will only move 1/4 the amount it is meant to. You need to add a jumper for the z-axis to make it work properly (or probably $2=1280, but I did not run like this because it reduces the z-axis torque). You can find more information <a href="https://github.com/synthetos/grblShield/wiki/Using-grblShield#wiki-microstepping">here</a>.</div>
<h2 style="clear: both; text-align: left;">
Toolchain / Workflow</h2>
<div>
Jumping in to CNC manufacturing is fairly overwhelming. I know a few things from work where we use Catia and a nice Hermle 5 axis (and by we I mean other people and I'm just peripherally involved). I spent some time reading around on various programs for both the CAD (design) and CAM (toolpaths) stage of things. My ideals were open source and runs nicely on a mac. I'm found something that satisfies it although it is possible I'll eventually fork over some money if these end up too limiting.</div>
<div>
<br /></div>
<div>
But I settled on two workflows, the former being the only thing I have used so far:</div>
<div>
<ul style="text-align: left;">
<li>Most things: FreeCAD for design and generating toolpasses with PyCAM</li>
<li>Artwork: Blender with the BlenderCAM add on (I've used Blender previously)</li>
</ul>
<div>
I really like <a href="http://www.freecadweb.org/">FreeCAD</a> so far because of the parametric modeling. I like the ability to simply type in the dimensions and angles and have it take care of the details. I recommend taking a look at <a href="http://hackaday.com/2014/02/05/3d-printering-making-a-thing-in-freecad-part-i/">this</a> tutorial. It also has a lot of similarities with what I learned from Catia. I'm using the 0.14 version right now, which I think isn't the official release. So far it's worked fairly well, although definitely has some bugs. So the first thing I did was a simple heart to try and convince my girlfriend this hobby is something she will like :).</div>
</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlWKNK9kY1xOBtXDkQqgGLgeBtgc-BnxRQruOAczsgp8Pks6CZcLgBfx6-Xn6wk_Q2pox8Yao009MQTIoYptdR0y4aGeOeLH9jIg3u2sRufv8eZ-8RpEBZx9R5nZDVuZnwCXrdFCoiZ6o/s1600/Screen+Shot+2014-02-22+at+10.19.26+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlWKNK9kY1xOBtXDkQqgGLgeBtgc-BnxRQruOAczsgp8Pks6CZcLgBfx6-Xn6wk_Q2pox8Yao009MQTIoYptdR0y4aGeOeLH9jIg3u2sRufv8eZ-8RpEBZx9R5nZDVuZnwCXrdFCoiZ6o/s1600/Screen+Shot+2014-02-22+at+10.19.26+AM.png" height="294" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg1JZVDoFCXxRjq6plGx3dII0GUDLk-T_Ko0MAAHs-A6NSbi-QrSlrMulxh-p12evDh94Tod1HyGnnx5jlvOAHbLt_ZUkcZ4EkGAvqMgDEJPIEIsFX7hLLyKGokNaSqQTs26LXDDV_9A5k/s1600/Screen+Shot+2014-02-22+at+10.19.38+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg1JZVDoFCXxRjq6plGx3dII0GUDLk-T_Ko0MAAHs-A6NSbi-QrSlrMulxh-p12evDh94Tod1HyGnnx5jlvOAHbLt_ZUkcZ4EkGAvqMgDEJPIEIsFX7hLLyKGokNaSqQTs26LXDDV_9A5k/s1600/Screen+Shot+2014-02-22+at+10.19.38+AM.png" height="291" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
I did this by using the draft mode to create the face (using two arcs and two straight lines) and then extruding that to make a solid. I realized afterwards this is NOT the right way to use FreeCAD so will talk about it later. From there I saved the shape as a .stl file and loaded it up in PyCAM.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
For PyCAM I would definitely recommend getting it from the source. The precompiled version I could only get a really silly toolpath that ended up taking a solid hour to cut. Tons of lifting the spindle up and then down, cut a little, and repeat. Unfortunately I forgot to save a screenshot of that ridiculousness. Anyway with the latest version I used the "waterline" cutting pattern to generate essentially what I wanted. </div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiLlm62GLESia6msQ93QcXyjfKSgMYd6WklrpJyZzNDWzmq4nRFWQ6XEhLM7z-Ow-8wfaDXUzaJs7Y3MqXhnvHP5HpzjD871bytVCM8e2K-RM1eWiXMIfNrmicYHr9P7yQjhNTdTemTbZg/s1600/Screen+Shot+2014-02-22+at+10.27.50+AM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiLlm62GLESia6msQ93QcXyjfKSgMYd6WklrpJyZzNDWzmq4nRFWQ6XEhLM7z-Ow-8wfaDXUzaJs7Y3MqXhnvHP5HpzjD871bytVCM8e2K-RM1eWiXMIfNrmicYHr9P7yQjhNTdTemTbZg/s1600/Screen+Shot+2014-02-22+at+10.27.50+AM.png" height="166" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
Although it would be nice to have the path in something not red since for me red on black is super low contrast. Luckily since it is OSS I can change that :D. Finally upload that path through the universal gcode sender and cut away :). These videos were taken with the earlier version of PyCAM so you'll see more silliness in the path.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhdfqYCbuKeuuTAk2uQVaDbirtd7FIhnSJol1bbAzH2zyKZ7rIrD62um3_oBcyr7ptNKRw1-0hHgwTKJbxnx1_6G4tBXfFRrEIarmkEZW-q2hfrgNeBVnyzbwPRlPiV_vugZSwAS6lc9sM/s1600/VID_20140218_232909.mp4" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhdfqYCbuKeuuTAk2uQVaDbirtd7FIhnSJol1bbAzH2zyKZ7rIrD62um3_oBcyr7ptNKRw1-0hHgwTKJbxnx1_6G4tBXfFRrEIarmkEZW-q2hfrgNeBVnyzbwPRlPiV_vugZSwAS6lc9sM/s1600/VID_20140218_232909.mp4" height="179" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
All of the cutting was done with the"<a href="https://www.inventables.com/technologies/solid-carbide-2-flute-straight-end-mill-10-pack">Solid Carbide 2 Flute</a>" bit from Inventables using some scrap wood I had sitting around.</div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiFOb0SDKrWeTCxT4cC9SFsGz15lADTEeaEKhIkJk83hDXRzc8AhzM_w5cxYQI7hkvSqnI6ORf31bVCNnCHZPRoPREhE0kGJ373w9EORPoY3XNXxbgIkg1O6pd7t0HJ3j79KXph2AXGUJA/s1600/VID_20140218_232637.mp4" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiFOb0SDKrWeTCxT4cC9SFsGz15lADTEeaEKhIkJk83hDXRzc8AhzM_w5cxYQI7hkvSqnI6ORf31bVCNnCHZPRoPREhE0kGJ373w9EORPoY3XNXxbgIkg1O6pd7t0HJ3j79KXph2AXGUJA/s1600/VID_20140218_232637.mp4" height="179" width="320" /></a></div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhxAP391PNi9LCC2MVQSUpdy3FkfJUDxgU6CXdZLDzhfIFF_LetbDEDx8PXrDYY7TFrkLMqNfTShuW-2QWdFFq_bYuzzspd6-i_oFwq9jHR6tCN8oqIYvNvIKCpFIU_hS8EPLeoZgZdyl8/s1600/VID_20140218_232047.mp4" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhxAP391PNi9LCC2MVQSUpdy3FkfJUDxgU6CXdZLDzhfIFF_LetbDEDx8PXrDYY7TFrkLMqNfTShuW-2QWdFFq_bYuzzspd6-i_oFwq9jHR6tCN8oqIYvNvIKCpFIU_hS8EPLeoZgZdyl8/s1600/VID_20140218_232047.mp4" height="179" width="320" /></a></div>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj1RvybTeuHOmVyhpWcr3iDL1JJOBeGa5cErZLRPRrx7EwN53SXf9b5VoGie65ttvFisZcesQ4ih0kCwjX7tR5q3mGovn5o2t7BwivBulz3Nzm1LEIzmA3CSzM01AyH41n8zCE6qV7YBxQ/s1600/IMG_20140222_104328.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj1RvybTeuHOmVyhpWcr3iDL1JJOBeGa5cErZLRPRrx7EwN53SXf9b5VoGie65ttvFisZcesQ4ih0kCwjX7tR5q3mGovn5o2t7BwivBulz3Nzm1LEIzmA3CSzM01AyH41n8zCE6qV7YBxQ/s1600/IMG_20140222_104328.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Happy Valentines day!</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
One question I did have after playing with this: what is the best place to designate as "0" for the tool. Right now I'm putting it towards the top of the material and then zeroing the coordinate system. However that ends up making my waste board a little sad when the material isn't the precise depth. I'm thinking about zeroing out on the table surface so that it can simply start a little high, but then it gets awkward because you need to move the material in and out for zeroing.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_AUwRGtMYvf3mc65e2OMWYN_dJFBseJdyxlOM0FbmeBazHgexFb1V0JSfvs5gAKGWKjHYl7it2Kp_HdMIvwJk3gZiG-DX34W2cNUSK1GEjbsh5Umb996epdH-DcCL-9L5ld0f09cxe1k/s1600/IMG_20140222_104332.jpg" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj_AUwRGtMYvf3mc65e2OMWYN_dJFBseJdyxlOM0FbmeBazHgexFb1V0JSfvs5gAKGWKjHYl7it2Kp_HdMIvwJk3gZiG-DX34W2cNUSK1GEjbsh5Umb996epdH-DcCL-9L5ld0f09cxe1k/s1600/IMG_20140222_104332.jpg" height="240" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Sad waste board</td></tr>
</tbody></table>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<h2 style="clear: both; text-align: left;">
More serious design</h2>
<div>
Now I knew the basics were working, I wanted to design something a bit more sophisticated. I'm trying to build a hinge that can be actuated in a fairly simple way and this will be a prototype of it. At this point I realized the right way to do this is using Part Design mode and creating constrained sketches. I'll defer to the <a href="http://hackaday.com/2014/02/05/3d-printering-making-a-thing-in-freecad-part-i/">hackaday tutorial</a> for details on how to do these things.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjoQUXzzn-ojaVc1LHZpqjtnheq_71pr0cnnK7Mm4BpOT5398xIY9HbTkKFRYwRWew4QbmYtFu2HcSsoZHWxpWoJDa01C4jeOekfMEjn4V0A-9N6GAnzAvQo38PKjcsWnaXo4qsW-4noNY/s1600/Screen+Shot+2014-02-22+at+11.10.42+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjoQUXzzn-ojaVc1LHZpqjtnheq_71pr0cnnK7Mm4BpOT5398xIY9HbTkKFRYwRWew4QbmYtFu2HcSsoZHWxpWoJDa01C4jeOekfMEjn4V0A-9N6GAnzAvQo38PKjcsWnaXo4qsW-4noNY/s1600/Screen+Shot+2014-02-22+at+11.10.42+AM.png" height="195" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Create the outline of the piece</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiCUc_kSwfQPDDN_DNabHndN0LKptXeuK2cdrNRuzIkMQbnlByHAEHpuErq_xQgeezPKqhOrCwhm9MSDJqfmPAfPo_fLPVOi_c0fF4Y4erLhNxCuSjO9zUI90w2dS_6_mPxqwNaHthxuCE/s1600/Screen+Shot+2014-02-22+at+11.10.57+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiCUc_kSwfQPDDN_DNabHndN0LKptXeuK2cdrNRuzIkMQbnlByHAEHpuErq_xQgeezPKqhOrCwhm9MSDJqfmPAfPo_fLPVOi_c0fF4Y4erLhNxCuSjO9zUI90w2dS_6_mPxqwNaHthxuCE/s1600/Screen+Shot+2014-02-22+at+11.10.57+AM.png" height="200" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Make it a pad that comes up</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgQ150whW4AQpe15RYggsMrVscosCR6HliqSGkKQLfPxIuHaHmwTqYUTAVW3v9MpTefzao53xgNXC6ligTo1T0mMTX4iTFkpf7YBy0AN31fohaGmyXja72jkqiGgHbXgLvWjDwY1GxFGBs/s1600/Screen+Shot+2014-02-22+at+11.14.05+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgQ150whW4AQpe15RYggsMrVscosCR6HliqSGkKQLfPxIuHaHmwTqYUTAVW3v9MpTefzao53xgNXC6ligTo1T0mMTX4iTFkpf7YBy0AN31fohaGmyXja72jkqiGgHbXgLvWjDwY1GxFGBs/s1600/Screen+Shot+2014-02-22+at+11.14.05+AM.png" height="153" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Make a sketch on the top face of how I want to shape a pocket</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiOewovd_7VOsvkKTXsK-nNPiPFMTMbwoAfEL-SWWiW52LZLkOwi8r1gvxxFSmEIXoK5sLT0kHx2Axg0qyjANnQSKaQst0BIgOwsoUAuw5Cl31YhLYtXi7uuNt0ssuz1bVnAB4WBhvEMdE/s1600/Screen+Shot+2014-02-22+at+11.14.19+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiOewovd_7VOsvkKTXsK-nNPiPFMTMbwoAfEL-SWWiW52LZLkOwi8r1gvxxFSmEIXoK5sLT0kHx2Axg0qyjANnQSKaQst0BIgOwsoUAuw5Cl31YhLYtXi7uuNt0ssuz1bVnAB4WBhvEMdE/s1600/Screen+Shot+2014-02-22+at+11.14.19+AM.png" height="162" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Add the filets at the corner to make it machinable</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjYKQNqZ1mlyhQQ5eLIrNOuMhTOx_wx57Y7j96GnbEiNjX4J4waemeS0Tfp0VOGxElUd-gajIgRXUBXIulGjIDX0yDRdsX6yZbQPy4M3aQH4YdB6Tsvd6p7951aJVxqZowqUna09nAZueQ/s1600/Screen+Shot+2014-02-22+at+11.19.24+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjYKQNqZ1mlyhQQ5eLIrNOuMhTOx_wx57Y7j96GnbEiNjX4J4waemeS0Tfp0VOGxElUd-gajIgRXUBXIulGjIDX0yDRdsX6yZbQPy4M3aQH4YdB6Tsvd6p7951aJVxqZowqUna09nAZueQ/s1600/Screen+Shot+2014-02-22+at+11.19.24+AM.png" height="165" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Get it fully constrained so it is valid. At this point it turns green.</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEigQvg1LUn7h0EN3n57AuppexhG-sO0icxvkFGJJkv7dNsDzqlK_VDtIq28XRKdAuu4yqBnMNzHKn_jcGoqc3Aa8EIEFPGcsrGTytkSSVuPPC34MO53SLFTaUb4nhbnerlTymZOdDYkwhw/s1600/Screen+Shot+2014-02-22+at+11.19.54+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEigQvg1LUn7h0EN3n57AuppexhG-sO0icxvkFGJJkv7dNsDzqlK_VDtIq28XRKdAuu4yqBnMNzHKn_jcGoqc3Aa8EIEFPGcsrGTytkSSVuPPC34MO53SLFTaUb4nhbnerlTymZOdDYkwhw/s1600/Screen+Shot+2014-02-22+at+11.19.54+AM.png" height="200" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Make a pocket in the piece that is that shape</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEije1FE9-lqgPYcEF4FXLXyBqNGNDbtTEoJVXvmhJnyIa3w-4xIseFsnBqoGogrC2YcRUP2xVH9TKyBSjNl6eCCGXIvpWMAbxpiYvt2HKvFWFsRI-Imf6xbvJI5C8aD3wZtnkbapR8v6WU/s1600/Screen+Shot+2014-02-22+at+11.23.16+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEije1FE9-lqgPYcEF4FXLXyBqNGNDbtTEoJVXvmhJnyIa3w-4xIseFsnBqoGogrC2YcRUP2xVH9TKyBSjNl6eCCGXIvpWMAbxpiYvt2HKvFWFsRI-Imf6xbvJI5C8aD3wZtnkbapR8v6WU/s1600/Screen+Shot+2014-02-22+at+11.23.16+AM.png" height="198" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">And another pocket at the end to lower the profile of the hinge area</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhj84hWB3p5EFbFf0PEY3sJEDKhKN0EUsS1Zzn5F2yyh0fMvT7_uQTo6ljypugL7Y3E8akYfJS7ya2ZIaZaGB-pyOx8exNz9hSkkKQ7Rjm1J6Rspc7V28sMun8Rx4GKOTXQ2igxfhEzEt4/s1600/Screen+Shot+2014-02-22+at+11.24.25+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhj84hWB3p5EFbFf0PEY3sJEDKhKN0EUsS1Zzn5F2yyh0fMvT7_uQTo6ljypugL7Y3E8akYfJS7ya2ZIaZaGB-pyOx8exNz9hSkkKQ7Rjm1J6Rspc7V28sMun8Rx4GKOTXQ2igxfhEzEt4/s1600/Screen+Shot+2014-02-22+at+11.24.25+AM.png" height="201" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">And finally a hole for where the opposite piece will mount</td></tr>
</tbody></table>
<h2 style="text-align: left;">
More serious CAM</h2>
<div>
From this model I exported the stl file and loaded it into PyCAM. </div>
<div>
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgUrf5lJIHpmAa9ys-forij3IP6jBM9y2hC4KZXjPxmL6qGXsXRjFnFSjw2RQDjulYF6VhVOhMZY43Qkb9PJFOVn3BQIilsvEC_1ljvu4oIrouiyNOhNq-3ZcXipApfVDHbSTD9oBwy5vs/s1600/Screen+Shot+2014-02-22+at+11.42.46+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgUrf5lJIHpmAa9ys-forij3IP6jBM9y2hC4KZXjPxmL6qGXsXRjFnFSjw2RQDjulYF6VhVOhMZY43Qkb9PJFOVn3BQIilsvEC_1ljvu4oIrouiyNOhNq-3ZcXipApfVDHbSTD9oBwy5vs/s1600/Screen+Shot+2014-02-22+at+11.42.46+AM.png" height="165" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Here you see the model all loaded up. Note this time "0" is below the piece which I need to remember</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgw2VwT6p-kMXzrVrgQvQDjNroJjiEABHhYy8r6YjlBgRrTUlxsYfckiwg_bqF1kNQYAH1R8Plcbpn0QHS8qWkmfdEuFuiwSr8_88RBe7SrbhxbXH5eLSFKs1PaDcIlOYnhomQVVwF9xfs/s1600/Screen+Shot+2014-02-22+at+11.47.57+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgw2VwT6p-kMXzrVrgQvQDjNroJjiEABHhYy8r6YjlBgRrTUlxsYfckiwg_bqF1kNQYAH1R8Plcbpn0QHS8qWkmfdEuFuiwSr8_88RBe7SrbhxbXH5eLSFKs1PaDcIlOYnhomQVVwF9xfs/s1600/Screen+Shot+2014-02-22+at+11.47.57+AM.png" height="312" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Tell PyCAM the bit I am using</td></tr>
</tbody></table>
So the strategy for cutting things out I like is "waterline" which goes around the edges. However, because I need to cut a big chunk of stock out I need to do this first because the drop down area won't be caught by the waterline strategy. I'll do this but restrict it to the part of the piece that is relevant.<br />
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi0jFOa0uuxczzGtWFThJS7rWjYTocR-LmpSz6ZiUvXqWd2E4FlSML7cpBbFtZpqszkTEQp2RoWgimrXxSlztYslvSK-WLtQ2QMWyyuefQei04LhVFPhpS1SKkYYvz2wp0ki5ZvA9y38Cs/s1600/Screen+Shot+2014-02-22+at+11.48.49+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEi0jFOa0uuxczzGtWFThJS7rWjYTocR-LmpSz6ZiUvXqWd2E4FlSML7cpBbFtZpqszkTEQp2RoWgimrXxSlztYslvSK-WLtQ2QMWyyuefQei04LhVFPhpS1SKkYYvz2wp0ki5ZvA9y38Cs/s1600/Screen+Shot+2014-02-22+at+11.48.49+AM.png" height="320" width="263" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">So a process named bulk removal that will be allowed to have some slop (0.5mm error)</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg9KAUAuN12Ui-g_NO3ezCWoilf0IUJYmmrXMvOJw5f9ANBxYCssr8cL64ieRhktcVA5vLClIiiu4YHTFKvdCafc0rjDEq2OoBQHV14Jvf8OPma6E6YoKTT0yW6_1_NXxjZJaVnl76MzMk/s1600/Screen+Shot+2014-02-22+at+11.49.00+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg9KAUAuN12Ui-g_NO3ezCWoilf0IUJYmmrXMvOJw5f9ANBxYCssr8cL64ieRhktcVA5vLClIiiu4YHTFKvdCafc0rjDEq2OoBQHV14Jvf8OPma6E6YoKTT0yW6_1_NXxjZJaVnl76MzMk/s1600/Screen+Shot+2014-02-22+at+11.49.00+AM.png" height="165" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Bounding box that only covers the area I need to remove material</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgbn5M7ZHRS0DHEFlCI8-AGCzGWXeQQZ2puqQPFrQiFttikci5J2NjgDk8sAvkRsZOgFn4RgDsNRBaJkylpmFjsRAQIRmvpsS9LyZW3lrMCGShvApjAj_rxn94C9w9ySfY3abxnRSfhXl4/s1600/Screen+Shot+2014-02-22+at+11.49.08+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgbn5M7ZHRS0DHEFlCI8-AGCzGWXeQQZ2puqQPFrQiFttikci5J2NjgDk8sAvkRsZOgFn4RgDsNRBaJkylpmFjsRAQIRmvpsS9LyZW3lrMCGShvApjAj_rxn94C9w9ySfY3abxnRSfhXl4/s1600/Screen+Shot+2014-02-22+at+11.49.08+AM.png" height="166" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Set up a task using these tools, strategies and area</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhDuStWnq6siU1pjUpszY-jPtHzGyBwmL1CJ84Ceoy4by_MR_VY6mN_q5KMcb-PkPjpixfVCL4LZShEKZtdq3Sr5Jxnl-RGYFuxyrDeTNLAHYyZo3H2QKmEp2oBHu-I8t5nWhTjN4NTSws/s1600/Screen+Shot+2014-02-22+at+11.49.16+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhDuStWnq6siU1pjUpszY-jPtHzGyBwmL1CJ84Ceoy4by_MR_VY6mN_q5KMcb-PkPjpixfVCL4LZShEKZtdq3Sr5Jxnl-RGYFuxyrDeTNLAHYyZo3H2QKmEp2oBHu-I8t5nWhTjN4NTSws/s1600/Screen+Shot+2014-02-22+at+11.49.16+AM.png" height="166" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Which gives a pretty reasonable path</td></tr>
</tbody></table>
<div>
Now that the stock is milled down there, waterline will work for the remaining area.</div>
<div class="separator" style="clear: both; text-align: center;">
<br /></div>
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiYEJkne6bd2NnGYcnqZDQACkt1ZvoEkWD0tbEmLihVGuUIwzG9qnBlviNZG81dZLLzdP6uIGXWgaRyVBJ72378LPrRGnySMJLkabwFl4oZiQy2pGlPHjtsiG2bqgojqoIjf_iGOSDDbWM/s1600/Screen+Shot+2014-02-22+at+11.52.43+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiYEJkne6bd2NnGYcnqZDQACkt1ZvoEkWD0tbEmLihVGuUIwzG9qnBlviNZG81dZLLzdP6uIGXWgaRyVBJ72378LPrRGnySMJLkabwFl4oZiQy2pGlPHjtsiG2bqgojqoIjf_iGOSDDbWM/s1600/Screen+Shot+2014-02-22+at+11.52.43+AM.png" height="320" width="259" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Use the waterline mode to cut around the edge</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj1zi9tkWlojUMzKp1yzWZqB-I0gTgS34gqvl3vvAMo5_qpSJjrgylc6OETq6pqwtRg2wyUyeUKONYuuE9gGfw4rPSepwjvxMsZvL7AUBwvTtswrBW4dqXtdwEWx4dFu6puR0MiJrvCXCE/s1600/Screen+Shot+2014-02-22+at+11.52.58+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEj1zi9tkWlojUMzKp1yzWZqB-I0gTgS34gqvl3vvAMo5_qpSJjrgylc6OETq6pqwtRg2wyUyeUKONYuuE9gGfw4rPSepwjvxMsZvL7AUBwvTtswrBW4dqXtdwEWx4dFu6puR0MiJrvCXCE/s1600/Screen+Shot+2014-02-22+at+11.52.58+AM.png" height="164" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Bounds that cover the whole model now</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgyBMkg6qinTqtbKD4qY7rZt5mHNFugXurCod1bP5N5pgMp0G3UaiUNvHlTDfQNn-y6ulFCyXZTXPOxz3RuQ0onrB4PDqtc_Ss5gTzKzryeEbuK3CkzJ_MhaUA0ehd3qHckSZJ1if0goyc/s1600/Screen+Shot+2014-02-22+at+11.53.03+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEgyBMkg6qinTqtbKD4qY7rZt5mHNFugXurCod1bP5N5pgMp0G3UaiUNvHlTDfQNn-y6ulFCyXZTXPOxz3RuQ0onrB4PDqtc_Ss5gTzKzryeEbuK3CkzJ_MhaUA0ehd3qHckSZJ1if0goyc/s1600/Screen+Shot+2014-02-22+at+11.53.03+AM.png" height="320" width="255" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">Set up a task to generate the pass using the correct process and bounds as well as the right collision model</td></tr>
</tbody></table>
<br />
<table align="center" cellpadding="0" cellspacing="0" class="tr-caption-container" style="margin-left: auto; margin-right: auto; text-align: center;"><tbody>
<tr><td style="text-align: center;"><a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwFUWXj5n0SvhlQSa7XZXyepl1mzbbcZ4GcpEt0VDtoe86Xdnyx66y7sf9u699bqNj7xPvSH4Cb6wCrJf4-mu9AK3gf76IqPsozKNd6PZ8MqQ_FYSf3Mc4KZdHsFNz6cNGJAiq3116398/s1600/Screen+Shot+2014-02-22+at+11.53.10+AM.png" imageanchor="1" style="margin-left: auto; margin-right: auto;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEiwFUWXj5n0SvhlQSa7XZXyepl1mzbbcZ4GcpEt0VDtoe86Xdnyx66y7sf9u699bqNj7xPvSH4Cb6wCrJf4-mu9AK3gf76IqPsozKNd6PZ8MqQ_FYSf3Mc4KZdHsFNz6cNGJAiq3116398/s1600/Screen+Shot+2014-02-22+at+11.53.10+AM.png" height="165" width="320" /></a></td></tr>
<tr><td class="tr-caption" style="text-align: center;">And finally the tool pass to generate this part</td></tr>
</tbody></table>
<div>
<br /></div>
<h2 style="clear: both; text-align: left;">
Cutting</h2>
<div>
I made a mistake the first time I generated this tool pass. I set the safety margin to 5mm which I had previously done when the "0" was on the top of the piece. In this case, that made the tool transverse between locations THROUGH the material. It took me a while to realize what was happening and it produced quite a mess. You can see this near the end of the video.<br />
<br /></div>
<div style="text-align: center;">
<iframe allowfullscreen="" frameborder="0" height="281" mozallowfullscreen="" src="//player.vimeo.com/video/87362150" webkitallowfullscreen="" width="500"></iframe> </div>
<div style="text-align: center;">
CNC Joint from <a href="http://vimeo.com/user4648573">James Cotton</a> on <a href="https://vimeo.com/">Vimeo</a>.</div>
<div style="text-align: center;">
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5RPI04JuKZWLtfwsRTSbQCkBzYDZy1kcCDV3syLI9eM42wDEVrMqtPO_quuEXIjk-GNuYpz4Cp1WNaqN4JexMwd6YUHo7xKo6HChTVxFM5rfbbHgIHVqcpVqmxytkBxZ733bTWqyj2q0/s1600/IMG_20140222_125333.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEg5RPI04JuKZWLtfwsRTSbQCkBzYDZy1kcCDV3syLI9eM42wDEVrMqtPO_quuEXIjk-GNuYpz4Cp1WNaqN4JexMwd6YUHo7xKo6HChTVxFM5rfbbHgIHVqcpVqmxytkBxZ733bTWqyj2q0/s1600/IMG_20140222_125333.jpg" height="240" width="320" /></a></div>
<div>
<br /></div>
<div>
My second pass was almost perfect. However, right at the end when it finished the middle hole the whole thing was disconnected and started spinning around. That ripped it nicely and luckily only bent the bit and didn't break anything. You have to be sitting by the power switch on this thing!</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjjeIjaoh7uCxWNByDZF1QD40nUWiPlqAiqr9XIL_CnTcKwTv4BKWux2OoIQOWGz73mLbkUngXxc7im-jrbvmSVcB8r1PtsA5YUwHiSaRpIQmj7NnF3-ORDPt731pTTg1x6Vx3P2V5uLio/s1600/IMG_20140222_134922.jpg" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjjeIjaoh7uCxWNByDZF1QD40nUWiPlqAiqr9XIL_CnTcKwTv4BKWux2OoIQOWGz73mLbkUngXxc7im-jrbvmSVcB8r1PtsA5YUwHiSaRpIQmj7NnF3-ORDPt731pTTg1x6Vx3P2V5uLio/s1600/IMG_20140222_134922.jpg" height="240" width="320" /></a></div>
<div>
<br /></div>
<div>
To work around this I went ahead and added a support structure:</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjm4NMWSBWPTxFw_2xQvGNgxBmTQfcT9iWRSlhF3XM80XrTqt5Cfwh6IM_BlTwxPh1tsLsk5RxB7UwOiEHXXp0EDBJCJhyd-jN2g5wsaUxWNBipG7mOpJwgKz5E0qDbYHWWZ1NHJA8_CgM/s1600/Screen+Shot+2014-02-22+at+1.40.28+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjm4NMWSBWPTxFw_2xQvGNgxBmTQfcT9iWRSlhF3XM80XrTqt5Cfwh6IM_BlTwxPh1tsLsk5RxB7UwOiEHXXp0EDBJCJhyd-jN2g5wsaUxWNBipG7mOpJwgKz5E0qDbYHWWZ1NHJA8_CgM/s1600/Screen+Shot+2014-02-22+at+1.40.28+PM.png" height="166" width="320" /></a></div>
<div>
<br /></div>
<div>
Which leaves it attached. However, I forgot to enable it for the collision detection so my second one almost went the same way. Luckily I stopped it in time and pulled the piece out. In the future I will definitely make sure to use supports properly and manually cut them when the piece is done.</div>
<div>
<br /></div>
<div>
Also for the final version I need to make sure the pocket inner cutting goes to the same depth as the waterline pass. That ended up not lining up perfectly and i'm not sure why yet.</div>
<h2 style="clear: both; text-align: left;">
Other component and finished!</h2>
<div>
I also machined the other side of the joint. This time I figured out how to use the grid cloning feature in PyCAM which was nice to make it one operation (which luckily didn't fail). This time I also got the supports to work properly.</div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlmGfONzIGy-pOZAG9UbbiZ7G5t9bEAlRMmFUpZDr53hm1rPtNvzPFnPhwq1t71axxOS421DU1DP5AM2I6DJuAFDnfhCy85cTz7pXX6RaHaiHkFHBKyGrQWXHIkCWl9DVohPLy-40h7gs/s1600/Screen+Shot+2014-02-22+at+4.53.11+PM.png" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlmGfONzIGy-pOZAG9UbbiZ7G5t9bEAlRMmFUpZDr53hm1rPtNvzPFnPhwq1t71axxOS421DU1DP5AM2I6DJuAFDnfhCy85cTz7pXX6RaHaiHkFHBKyGrQWXHIkCWl9DVohPLy-40h7gs/s1600/Screen+Shot+2014-02-22+at+4.53.11+PM.png" height="236" width="320" /></a></div>
<div>
<br /></div>
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjwU104i1c4FgQUlgZAtLWf0UCWOPVxguwHxTdWvq3KutQDyJPcJzZmSOnV5vHeYnEle1q3UOVOM9MfzgfzIbRgHxcFQLCQOq9GVWz8MTMz988VpyjGPfgKD3gOHsEExs2UtXZ05L9-VZE/s1600/DSC02142.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjwU104i1c4FgQUlgZAtLWf0UCWOPVxguwHxTdWvq3KutQDyJPcJzZmSOnV5vHeYnEle1q3UOVOM9MfzgfzIbRgHxcFQLCQOq9GVWz8MTMz988VpyjGPfgKD3gOHsEExs2UtXZ05L9-VZE/s1600/DSC02142.JPG" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhI0kabjaYq7fwU5lROvlNtCrA8wrGVV_8ly29G_5xkpk0XHLkDVk5qOfk1OTgSx3hFdyaoXDz9n8QM2yr4eg8ORFsGQItTMYLRJ50IKHrIk9AthrCLaBnQMaAt924GbedA_0f28YPthPE/s1600/DSC02144.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEhI0kabjaYq7fwU5lROvlNtCrA8wrGVV_8ly29G_5xkpk0XHLkDVk5qOfk1OTgSx3hFdyaoXDz9n8QM2yr4eg8ORFsGQItTMYLRJ50IKHrIk9AthrCLaBnQMaAt924GbedA_0f28YPthPE/s1600/DSC02144.JPG" height="212" width="320" /></a></div>
<br />
<div class="separator" style="clear: both; text-align: center;">
<a href="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlFPZ8ZEr5-_e76Q40zJNqq_0ctd6o_YYnUElbIZ0rn9mJ0HTht_DO_urbv1LWaqNKvMzZKUhbA1it6bwqCnpMOhtV_v316phyOcXP67W6wR0WqPNLHUaZcOeXiKTBjBsz_dFLnZC8vhU/s1600/DSC02146.JPG" imageanchor="1" style="margin-left: 1em; margin-right: 1em;"><img border="0" src="https://blogger.googleusercontent.com/img/b/R29vZ2xl/AVvXsEjlFPZ8ZEr5-_e76Q40zJNqq_0ctd6o_YYnUElbIZ0rn9mJ0HTht_DO_urbv1LWaqNKvMzZKUhbA1it6bwqCnpMOhtV_v316phyOcXP67W6wR0WqPNLHUaZcOeXiKTBjBsz_dFLnZC8vhU/s1600/DSC02146.JPG" height="212" width="320" /></a></div>
<div>
<br /></div>
<h2 style="clear: both; text-align: left;">
Thanks Inventables</h2>
<div>
Both for making this available at a reasonable cost and having pretty good documentation. Also it just seems like a company run by people that are nice which is awesome. When there was a mixup on some shipping stuff they paid the difference even when I offered to, which is just really nice.</div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div class="separator" style="clear: both; text-align: left;">
<br /></div>
<div>
<br /></div>
</div>
Jameshttp://www.blogger.com/profile/03069033000874572139noreply@blogger.com5