changeset 170:e80340fe527a

merge
author Giulio Moro <giuliomoro@yahoo.it>
date Mon, 28 Dec 2015 03:19:59 +0100
parents 94751ad27fd6 (current diff) eb62ed0d67e3 (diff)
children e63563507edd
files
diffstat 27 files changed, 2370 insertions(+), 1 deletions(-) [+]
line wrap: on
line diff
--- a/Makefile	Mon Dec 28 03:17:22 2015 +0100
+++ b/Makefile	Mon Dec 28 03:19:59 2015 +0100
@@ -87,7 +87,7 @@
 build/source/%.o: ./source/%.c
 	@echo 'Building file: $<'
 	@echo 'Invoking: GCC C Compiler'
-	gcc $(SYNTAX_FLAG) -I./include $(INCLUDES) -O2 -Wall -c -fmessage-length=0 -U_FORTIFY_SOURCE -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<"
+	gcc $(SYNTAX_FLAG) -I./include $(INCLUDES) -O2 -Wall -c -fmessage-length=0 -U_FORTIFY_SOURCE -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@:%.o=%.d)" -o "$@" "$<" -std=c99
 	@echo 'Finished building: $<'
 	@echo ' '
 
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/Junction.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,95 @@
+/*
+ *
+ * Excitation Junction for two waveguides
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#include "Junction.h"
+#include "../include/Utilities.h"
+
+Junction::Junction()	{
+
+	setFrequency(440);
+	_dt = 1.0/44100.0;
+
+	// initialize variables
+	for(int i=0;i<WG_BUFFER_SIZE;i++)	{
+		_buffer_l[i] = 0;
+		_buffer_r[i] = 0;
+	}
+	_excitation = 0;
+	_lastPlectrumDisplacement = 0;
+	_readPtr = 0;
+
+}
+
+void Junction::update(float excitation, float left, float right)	{
+
+	// 1. advance delay buffer read pointer
+
+	if(++_readPtr>=WG_BUFFER_SIZE)
+		_readPtr=0;
+
+	// 2. add excitation sample into buffer
+
+	_buffer_l[(_readPtr+_delay_l+WG_BUFFER_SIZE)%WG_BUFFER_SIZE] = excitation;
+	_buffer_r[(_readPtr+_delay_r+WG_BUFFER_SIZE)%WG_BUFFER_SIZE] = excitation;
+
+	// 3. feed right input to left output and vice versa
+
+	_buffer_l[_readPtr] += right;
+	_buffer_r[_readPtr] += left;
+
+	// 4. store excitation value for later use
+	_excitation = excitation;
+
+}
+
+float Junction::getOutput(int direction)	{
+
+	if(direction = 0)
+		return _buffer_l[_readPtr];
+	else
+		return _buffer_r[_readPtr];
+
+}
+
+float Junction::getExcitationDisplacement()	{
+
+	// string displacement and excitation force
+	// use delayed value to account for excitation position
+	float in = _buffer_l[(_readPtr+_delay_l+WG_BUFFER_SIZE)%WG_BUFFER_SIZE] + _excitation;
+
+	// integrate total force
+	float out = 0.00001 * in + 0.99999 * _lastPlectrumDisplacement;
+
+	// store variable for next iteration
+	_lastPlectrumDisplacement = out;
+
+	// multiply by delta time
+	return out * _dt;
+
+}
+
+void Junction::setPluckPosition(float pluckPos){
+
+	pluckPos = constrain(pluckPos,0,1);
+	_delay_l = pluckPos * _periodInSamples;
+	_delay_r = (1-pluckPos) * _periodInSamples;
+
+}
+
+void Junction::setPeriod(float period)	{
+
+	_periodInMilliseconds = period;
+
+}
+
+void Junction::setFrequency(float frequency)	{
+
+	_periodInMilliseconds = 1000.0/frequency;
+	_periodInSamples = (int)(_periodInMilliseconds * 44.1);
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/Junction.h	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,54 @@
+/*
+ *
+ * Excitation Junction for two waveguides
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#ifndef JUNCTION_H_
+#define JUNCTION_H_
+
+#include <cmath>
+
+#ifndef WG_BUFFER_SIZE
+#define WG_BUFFER_SIZE 4096
+#endif
+
+#ifndef		M_PI
+#define		M_PI		3.14159265358979323846264338
+#endif
+
+class Junction
+{
+
+public:
+
+	Junction();
+	void setup();
+	void update(float excitation, float left, float right);
+	float getOutput(int direction);
+	float getExcitationDisplacement();
+	void setFrequency(float frequency);
+	void setPeriod(float periodInMs);
+	void setPluckPosition(float pluckPos);
+
+private:
+
+	double _dt;
+	float _periodInMilliseconds;
+	int _periodInSamples;
+
+	int _delay_l;
+	int _delay_r;
+
+	float _buffer_l[WG_BUFFER_SIZE];
+	float _buffer_r[WG_BUFFER_SIZE];
+	int _readPtr;
+
+	float _excitation;
+	float _lastPlectrumDisplacement;
+
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/MassSpringDamper.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,59 @@
+/*
+ *
+ * Simple 1-Dimensional Mass Spring Damper
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#include "MassSpringDamper.h"
+
+MassSpringDamper::MassSpringDamper(float mass, float spring, float damp)	{
+
+	_dt = 1.0/44100.0;
+	_mass = mass;
+	_spring = spring;
+	_damp = damp;
+	_position = 0;
+	_velocity = 0;
+
+}
+
+void MassSpringDamper::setup()	{
+
+}
+
+double MassSpringDamper::update(float inForce)	{
+
+	// 1. calculate spring/damper forces using current position and velocity
+
+	double out = (_position * (double)_spring * -1) + (_velocity * (double)_damp * -1);
+
+	// 2. apply external force
+
+	out += inForce;
+
+	// 3. derive acceleration (a = f/m)
+
+	out /= (double)_mass;
+
+	// 4. derive velocity (v = a*dt)
+
+	out *= _dt;
+
+	// 5. apply previous velocity
+
+	out += _velocity;
+
+	// 6. save current velocity state for next iteration
+
+	_velocity = out;
+
+	// 7. derive new position (x[n] = x[n-1] + v[n]) and save for next iteration
+
+	out += _position;
+	_position = out;
+
+	return out;
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/MassSpringDamper.h	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,32 @@
+/*
+ *
+ * Simple 1-Dimensional Mass Spring Damper
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#ifndef MASSSPRINGDAMPER_H_
+#define MASSSPRINGDAMPER_H_
+
+class MassSpringDamper
+{
+
+public:
+
+	MassSpringDamper(float mass, float spring, float damp);
+	void setup();
+	double update(float inForce);
+
+private:
+
+	double _dt;
+	float _mass;
+	float _spring;
+	float _damp;
+	double _position;
+	double _velocity;
+
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/Plectrum.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,61 @@
+/*
+ *
+ * Plectrum model for touching and plucking strings
+ *
+ * Christian Heinrichs 04/2015
+ *
+ * [inspired by E. Berdahl's pluck~ abstraction for the FireFader]
+ *
+ */
+
+#include "Plectrum.h"
+
+#include "../include/Utilities.h"
+#include <cmath>
+#include <stdio.h>
+#include <cstdlib>
+
+Plectrum::Plectrum()	{
+
+	_contact = 0;
+	_lastDistance = 0;
+
+}
+
+void Plectrum::setup(float spring, float damp, float hyst)	{
+
+	_spring = spring;
+	_damp = damp;
+	_hyst = hyst;
+
+}
+
+float Plectrum::update(float position, float stringPosition)	{
+
+	float distance = position - stringPosition;
+
+	// Calculate spring/damp forces based on distance to string
+
+	float springOut = distance * _spring;
+
+	float dampOut = (distance - _lastDistance) * 44100;
+
+	float out = springOut+dampOut;
+
+	// If distance crosses zero, enable contact
+
+	if((distance>0 && _lastDistance<=0)||(distance<0 && _lastDistance>=0))
+		_contact = 1;
+
+	// If distance exceeds hysteresis threshold, jump to zero (i.e. 'pluck')
+
+	if(fabs(distance)>_hyst)
+		_contact = 0;
+
+	// FIXME: contact doesn't switch back to zero if distance goes back in original direction
+
+	_lastDistance = distance;
+
+	return out * _contact;
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/Plectrum.h	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,35 @@
+/*
+ *
+ * Plectrum model for touching and plucking strings
+ *
+ * [inspired by E. Berdahl's pluck~ abstraction for the FireFader]
+ *
+ */
+
+#ifndef PLECTRUM_H_
+#define PLECTRUM_H_
+
+class Plectrum
+{
+
+public:
+
+	Plectrum();
+	void setup(float spring, float damp, float hyst);
+	float update(float position, float stringPosition);
+
+private:
+
+	double _dt;
+	float _spring;
+	float _damp;
+	double _position;
+	double _velocity;
+	float _hyst;
+	float _lastDistance;
+	int _contact;
+
+};
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/String.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,91 @@
+/*
+ *
+ * 1-D string consisting of two waveguides and junction
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#include "String.h"
+#include "Junction.h"
+#include "Waveguide.h"
+
+#include "../include/Utilities.h"
+#include <rtdk.h>
+#include <cmath>
+#include <stdio.h>
+#include <cstdlib>
+
+String::String(){
+
+	wg_l = Waveguide();
+	wg_r = Waveguide();
+	junction = Junction();
+
+	junction.setPluckPosition(0.5);
+
+	_previous_l = 0;
+	_previous_r = 0;
+
+}
+
+float String::update(float in)	{
+
+	// 1. send excitation signal and previous waveguide outputs into junction
+
+	junction.update(in,_previous_l,_previous_r);
+
+	// 2. save new waveguide outputs for next iteration
+
+	_previous_l = wg_l.update(junction.getOutput(0));
+	_previous_r = wg_r.update(junction.getOutput(1));
+
+	// 3. use right waveguide as output
+
+	//rt_printf("BANANA %f ",_readPtr);
+	//rt_printf("%f\n",_previous_r);
+
+	return _previous_r;
+}
+
+float String::getPlectrumDisplacement()	{
+
+	return junction.getExcitationDisplacement();
+
+}
+
+void String::setPluckPosition(float pluckPos){
+
+	junction.setPluckPosition(pluckPos);
+
+}
+
+void String::setGlobalPosition(float pos)	{
+
+	_globalPosition = pos;
+
+}
+
+float String::getGlobalPosition()	{
+
+	return _globalPosition;
+
+}
+
+void String::setMidinote(float midinote)	{
+
+	float frequency = 440.0f*(float)powf(2,(midinote-57)/12.0f);
+
+	junction.setFrequency(frequency);
+	wg_l.setFrequency(frequency);
+	wg_r.setFrequency(frequency);
+
+}
+
+void String::setFrequency(float frequency)	{
+
+	junction.setFrequency(frequency);
+	wg_l.setFrequency(frequency);
+	wg_r.setFrequency(frequency);
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/String.h	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,45 @@
+/*
+ *
+ * 1-D string consisting of two waveguides and junction
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#ifndef STRING_H_
+#define STRING_H_
+
+#include <cmath>
+#include "Junction.h"
+#include "Waveguide.h"
+
+class String
+{
+
+public:
+
+	String();
+	float update(float in);
+
+	float getPlectrumDisplacement();
+	void setMidinote(float midinote);
+	void setFrequency(float frequency);
+	void setPeriod(float periodInMs);
+	void setPluckPosition(float pluckPos);
+	void setGlobalPosition(float pos);
+	float getGlobalPosition();
+
+private:
+
+	float _previous_l;
+	float _previous_r;
+
+	float _globalPosition;
+
+	Waveguide wg_l;
+	Waveguide wg_r;
+	Junction junction;
+
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/Waveguide.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,128 @@
+/*
+ *
+ * Simple 1-Dimensional Waveguide
+ *
+ */
+
+#include "Waveguide.h"
+#include "../include/Utilities.h"
+#include <rtdk.h>
+#include <cmath>
+#include <stdio.h>
+#include <cstdlib>
+
+#define DECAY 0.995//0.999
+#define DAMPING 0.01//0.05
+
+// TODO: make damping and decay parametrisable
+
+Waveguide::Waveguide()	{
+
+	// initialize variables
+	a1_lp = 0;
+	a2_lp = 0;
+	b0_lp = 0;
+	b1_lp = 0;
+	b2_lp = 0;
+	_dt = 1.0/44100.0;
+	setFrequency(440);
+	updateFilterCoeffs(8000);
+	_filterReadPtr=0;
+	for(int i=0;i<FILTER_BUFFER_SIZE;i++)	{
+		_filterBuffer_x[i] = 0;
+		_filterBuffer_y[i] = 0;
+	}
+	for(int i=0;i<WG_BUFFER_SIZE;i++)	{
+		_buffer[i] = 0;
+	}
+	_lastX = 0;
+	_lastY = 0;
+	_readPtr = 0;
+
+}
+
+void Waveguide::setup()	{
+
+}
+
+float Waveguide::update(float in)	{
+
+	// 1. advance delay buffer read pointer
+
+	if(++_readPtr>=WG_BUFFER_SIZE)
+		_readPtr=0;
+
+	// 2. write input into buffer
+
+	_buffer[_readPtr] = in;
+
+	// 3. read delayed sample from buffer
+
+	float out = _buffer[(_readPtr-_periodInSamples+WG_BUFFER_SIZE)%WG_BUFFER_SIZE];
+
+	// 4. apply damping (low-pass) filter to output
+
+	if(++_filterReadPtr>=FILTER_BUFFER_SIZE)
+			_filterReadPtr=0;
+
+	out = b0_lp*out +
+					b1_lp*_filterBuffer_x[(_filterReadPtr-1+FILTER_BUFFER_SIZE)%FILTER_BUFFER_SIZE] +
+					b2_lp*_filterBuffer_x[(_filterReadPtr-2+FILTER_BUFFER_SIZE)%FILTER_BUFFER_SIZE] -
+					a1_lp*_filterBuffer_y[(_filterReadPtr-1+FILTER_BUFFER_SIZE)%FILTER_BUFFER_SIZE] -
+					a2_lp*_filterBuffer_y[(_filterReadPtr-2+FILTER_BUFFER_SIZE)%FILTER_BUFFER_SIZE];
+
+	// 5. Simple high-pass filter to block DC-offset
+	// y[n] = x[n] - x[n-1] + a * y[n-1]
+	float gain = 0.9999;
+	float temp = out;
+	out = out - _lastX + gain * _lastY;
+	_lastY = out;
+	_lastX = temp;
+
+	// 6. Apply intensity damping
+	out *= DECAY;
+
+	_filterBuffer_x[_filterReadPtr] = in;
+	_filterBuffer_y[_filterReadPtr] = out;
+
+	return out;
+
+}
+
+void Waveguide::setFrequency(float frequency)	{
+
+	// NB: currently no interpolation, so may not be ideal for dynamically changing waveguide frequency
+	_periodInMilliseconds = 1000.0/frequency;
+	_periodInSamples = (int)(_periodInMilliseconds * 44.1);
+
+}
+
+void Waveguide::updateFilterCoeffs(float frequency)	{
+
+	// FIXME: Butterworth filter doesn't work very well,
+	//		  using simple FIR in the meantime
+
+	a1_lp = 0;
+	a2_lp = 0;
+	b0_lp = 1.0 - DAMPING;
+	b1_lp = DAMPING;
+	b2_lp = 0;
+
+	/*
+	// 'w' for sake of resembling lower-case 'omega'
+	float w = 2.0 * M_PI * frequency;
+	float t = _dt;
+	// The Q for a 2nd-order Butterworth is sqrt(2)/2
+	float q = 0.707;//sqrt(2.0)/2.0;
+
+	// low-pass filter coefficients
+	float a0_lp = w*w*t*t + 2*(w/q)*t + 4.0;
+	float k = 1.0/a0_lp;
+	a1_lp = (2.0*w*w*t*t - 8.0) * k;
+	a2_lp = (4.0 - (w/q)*2.0*t + w*w*t*t) * k;
+	b0_lp = (w*w*t*t) * k;
+	b1_lp = (2.0*w*w*t*t) * k;
+	b2_lp = (w*w*t*t) * k;
+	*/
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/Waveguide.h	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,57 @@
+/*
+ *
+ * Simple 1-Dimensional Waveguide
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+#ifndef WAVEGUIDE_H_
+#define WAVEGUIDE_H_
+
+#include <cmath>
+
+#ifndef WG_BUFFER_SIZE
+#define WG_BUFFER_SIZE 4096
+#endif
+
+#ifndef FILTER_BUFFER_SIZE
+#define FILTER_BUFFER_SIZE 4
+#endif
+
+#ifndef		M_PI
+#define		M_PI		3.14159265358979323846264338
+#endif
+
+class Waveguide
+{
+
+public:
+
+	Waveguide();
+	void setup();
+	float update(float in);
+	void updateFilterCoeffs(float frequency);
+	void setFrequency(float frequency);
+
+private:
+
+	double _dt;
+	float _periodInMilliseconds;
+	int _periodInSamples;
+
+	float _buffer[WG_BUFFER_SIZE];
+	int _readPtr;
+
+	float _filterBuffer_x[FILTER_BUFFER_SIZE];
+	float _filterBuffer_y[FILTER_BUFFER_SIZE];
+	float _hipBuffer_x[FILTER_BUFFER_SIZE];
+	float _hipBuffer_y[FILTER_BUFFER_SIZE];
+	int _filterReadPtr;
+
+	float b0_lp,b1_lp,b2_lp,a1_lp, a2_lp;
+	float _lastY,_lastX;
+
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/airharp/render.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,212 @@
+/*
+ * AIR-HARP
+ * Physically modelled strings using waveguide junctions and mass-spring-dampers
+ *
+ * render.cpp
+ *
+ * Christian Heinrichs 04/2015
+ *
+ */
+
+
+#include "MassSpringDamper.h"
+#include "String.h"
+#include "Plectrum.h"
+
+#include <BeagleRT.h>
+#include <cmath>
+#include <stdio.h>
+#include <cstdlib>
+#include <rtdk.h>
+#include "../include/Utilities.h"
+
+#define ACCEL_BUF_SIZE 8
+#define NUMBER_OF_STRINGS 9
+
+// PENTATONIC SCALE
+float gMidinotes[NUMBER_OF_STRINGS] = {40,45,50,55,57,60,62,64,67};
+
+float gInverseSampleRate;
+
+float out_gain = 5.0;
+
+int accelPin_x = 0;
+int accelPin_y = 1;
+int accelPin_z = 2;
+
+MassSpringDamper msd = MassSpringDamper(1,0.1,10);// (10,0.001,10);
+String strings[NUMBER_OF_STRINGS];
+Plectrum plectrums[NUMBER_OF_STRINGS];
+
+float gPlectrumDisplacement = 0;
+
+float gAccel_x[ACCEL_BUF_SIZE] = {0};
+int gAccelReadPtr = 0;
+
+// DC BLOCK BUTTERWORTH
+
+// Coefficients for 100hz cut-off
+float a0_l = 0.9899759179893742;
+float a1_l = -1.9799518359787485;
+float a2_l = 0.9899759179893742;
+float a3_l = -1.979851353142371;
+float a4_l = 0.9800523188151258;
+
+float a0_r = a0_l;
+float a1_r = a1_l;
+float a2_r = a2_l;
+float a3_r = a3_l;
+float a4_r = a4_l;
+
+float x1_l = 0;
+float x2_l = 0;
+float y1_l = 0;
+float y2_l = 0;
+
+float x1_r = 0;
+float x2_r = 0;
+float y1_r = 0;
+float y2_r = 0;
+
+
+bool setup(BeagleRTContext *context, void *userData)
+{
+
+	gInverseSampleRate = 1.0 / context->audioSampleRate;
+
+	// initialise strings & plectrums
+	for(int i=0;i<NUMBER_OF_STRINGS;i++)	{
+
+		plectrums[i] = Plectrum();
+		plectrums[i].setup(250,0.25,0.05);
+
+		strings[i] = String();
+		strings[i].setMidinote(gMidinotes[i]);
+
+		float spacing = 2.0 / (NUMBER_OF_STRINGS+1);
+
+		strings[i].setGlobalPosition( -1 + spacing*(i+1) );
+
+		rt_printf("STRING %d // midinote: %f position: %f\n",i,gMidinotes[i],( -1 + spacing*(i+1) ));
+
+	}
+
+	return true;
+}
+
+void render(BeagleRTContext *context, void *userData)
+{
+
+	float lastAccel = 0;
+
+	for(int n = 0; n < context->audioFrames; n++) {
+
+		/*
+		 *
+		 * ACCELEROMETER DATA
+		 *
+		 */
+
+		// Read accelerometer data from analog input
+		float accel_x = 0;
+		if(n%2)	{
+			accel_x = (float)context->analogIn[(n/2)*8+accelPin_x] * 2 - 1;	// 15800 - 28300 - 41500
+			lastAccel = accel_x;
+		} else {
+			// grab previous value if !n%2
+			accel_x = lastAccel;
+		}
+
+		// Dead-zone avoids noise when box is lying horizontally on a surface
+
+		float accelDeadZone = 0.1;
+
+		if(accel_x <= accelDeadZone && accel_x >= -accelDeadZone)
+			accel_x = 0;
+
+		// Perform smoothing (moving average) on acceleration value
+		if(++gAccelReadPtr >= ACCEL_BUF_SIZE)
+			gAccelReadPtr = 0;
+		gAccel_x[gAccelReadPtr] = accel_x;
+		float gravity = 0;
+		for(int i=0;i<ACCEL_BUF_SIZE;i++)	{
+			gravity = gAccel_x[(gAccelReadPtr-i+ACCEL_BUF_SIZE)%ACCEL_BUF_SIZE];
+		}
+		gravity /= ACCEL_BUF_SIZE;
+
+		/*
+		 *
+		 * PHYSICS SIMULATION
+		 *
+		 */
+
+		// The horizontal force (which can be gravity if box is tipped on its side)
+		// is used as the input to a Mass-Spring-Damper model
+		// Plectrum displacement (i.e. when interacting with string) is included
+		float massPosition = (float)msd.update(gravity - gPlectrumDisplacement);
+
+		float out_l = 0;
+		float out_r = 0;
+		// Use this parameter to quickly adjust output gain
+		float gain = 0.0015;	// 0.0015 is a good value or 12 strings
+		gPlectrumDisplacement = 0;
+
+		for(int s=0;s<NUMBER_OF_STRINGS;s++)	{
+
+			float stringPosition = strings[s].getGlobalPosition();
+
+			float plectrumForce = plectrums[s].update(massPosition, stringPosition);
+			gPlectrumDisplacement += strings[s].getPlectrumDisplacement();
+
+			// calculate panning based on string position (-1->left / 1->right)
+			float panRight = map(stringPosition,1,-1,0.1,1);
+			float panLeft = map(stringPosition,-1,1,0.1,1);
+			panRight *= panRight;
+			panLeft *= panLeft;
+
+			float out = strings[s].update(plectrumForce)*gain;
+
+			out_l += out*panLeft;
+			out_r += out*panRight;
+
+		}
+
+		// APPLY DC-BLOCK FILTER TO OUTPUTS
+
+		// LEFT CHANNEL
+		float temp_in = out_l;
+		/* compute result */
+    	out_l = a0_l * out_l + a1_l * x1_l + a2_l * x2_l - a3_l * y1_l - a4_l * y2_l;
+    	/* shift x1 to x2, sample to x1 */
+    	x2_l = x1_l;
+    	x1_l = temp_in;
+    	/* shift y1 to y2, result to y1 */
+    	y2_l = y1_l;
+   	 	y1_l = out_l;
+
+   	 	// RIGHT CHANNEL
+		temp_in = out_r;
+		/* compute result */
+    	out_r = a0_r * out_r + a1_r * x1_r + a2_r * x2_r - a3_r * y1_r - a4_r * y2_r;
+    	/* shift x1 to x2, sample to x1 */
+    	x2_r = x1_r;
+    	x1_r = temp_in;
+    	/* shift y1 to y2, result to y1 */
+    	y2_r = y1_r;
+   	 	y1_r = out_r;
+
+		context->audioOut[n * context->audioChannels + 1] = out_l * out_gain;
+		context->audioOut[n * context->audioChannels + 0] = out_r * out_gain;
+
+	}
+
+}
+
+
+// cleanup_render() is called once at the end, after the audio has stopped.
+// Release any resources that were allocated in initialise_render().
+
+void cleanup(BeagleRTContext *context, void *userData)
+{
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/basicAnalogIn/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,30 @@
+#N canvas 203 356 637 339 10;
+#X obj 63 170 osc~ 440;
+#X obj 63 223 dac~;
+#X obj 63 191 *~;
+#X text 440 95 ADC 3: Analog In 0;
+#X text 34 41 Basic analog in (or 'theremin');
+#X text 34 51 ===============================;
+#X text 121 105 << Use first two analog in's;
+#X text 440 49 ADC routing:;
+#X text 440 57 ------------;
+#X text 440 105 ADC 4: Analog In 1;
+#X text 440 115 ADC 5: Analog In 2;
+#X text 440 125 ADC 6: Analog In 3;
+#X text 440 135 ADC 7: Analog In 4;
+#X text 440 145 ADC 8: Analog In 5;
+#X text 440 155 ADC 9: Analog In 6;
+#X text 440 165 ADC 10: Analog In 7;
+#X text 440 75 ADC 1: Audio In L;
+#X text 440 85 ADC 2: Audio In R;
+#X obj 63 149 *~ 880;
+#X obj 63 106 adc~ 3 4;
+#X text 355 277 ---------------------------------;
+#X text 355 267 @krighxz / BELA / heavy / 12/2015;
+#X text 379 286 beaglert.cc / enzienaudio.com;
+#X connect 0 0 2 0;
+#X connect 2 0 1 0;
+#X connect 2 0 1 1;
+#X connect 18 0 0 0;
+#X connect 19 0 18 0;
+#X connect 19 1 2 1;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/basicAnalogOut/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,30 @@
+#N canvas 275 504 679 362 10;
+#X text 148 124 << Use first two analog in's;
+#X text 431 57 ------------;
+#X text 44 51 Basic analog out;
+#X text 44 61 ================;
+#X text 431 95 DAC 3: Analog Out 0;
+#X text 431 105 DAC 4: Analog Out 1;
+#X text 431 115 DAC 5: Analog Out 2;
+#X text 431 125 DAC 6: Analog Out 3;
+#X text 431 145 DAC 8: Analog Out 5;
+#X text 431 135 DAC 7: Analog Out 4;
+#X text 431 155 DAC 9: Analog Out 6;
+#X text 431 165 DAC 10: Analog Out 7;
+#X text 431 85 DAC 2: Audio Out R;
+#X text 431 75 DAC 1: Audio Out L;
+#X obj 92 201 *~;
+#X obj 92 159 *~ 10;
+#X obj 92 180 osc~ 1;
+#X obj 35 242 dac~ 1 2 3;
+#X text 143 241 << Output to first analog out;
+#X text 431 49 DAC routing:;
+#X text 432 289 ---------------------------------;
+#X text 432 279 @krighxz / BELA / heavy / 12/2015;
+#X text 456 298 beaglert.cc / enzienaudio.com;
+#X obj 92 125 adc~ 3 4;
+#X connect 14 0 17 2;
+#X connect 15 0 16 0;
+#X connect 16 0 14 0;
+#X connect 23 0 15 0;
+#X connect 23 1 14 1;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/circularBuffer/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,79 @@
+#N canvas 436 490 738 494 10;
+#X obj 135 167 loadbang;
+#X msg 135 212 1;
+#X obj 183 234 / 44.1;
+#X obj 135 253 metro;
+#X obj 135 286 f;
+#X obj 160 286 + 64;
+#X obj 160 308 % 65536, f 8;
+#X msg 160 329 start \$1;
+#X obj 160 351 tabwrite~ circbuf;
+#X obj 363 303 - 32768;
+#X obj 363 325 + 65536;
+#X obj 363 347 % 65536;
+#X obj 342 371 +~ 0;
+#X msg 381 236 0;
+#X obj 342 258 phasor~;
+#X obj 342 392 tabread4~ circbuf;
+#X obj 341 415 dac~;
+#N canvas 422 781 312 126 buf 0;
+#N canvas 0 22 450 278 (subpatch) 0;
+#X array circbuf 65536 float 2;
+#X coords 0 1 65535 -1 256 64 1 0 0;
+#X restore 23 28 graph;
+#X restore 129 441 pd buf;
+#X obj 32 101 osc~ 440;
+#X obj 342 213 samplerate~;
+#X obj 134 189 t b b b b;
+#X text 30 82 audio input;
+#X text 219 310 write pointer;
+#X text 412 349 read pointer;
+#X obj 342 282 *~ 16;
+#X obj 342 236 / 16;
+#X obj 183 214 f 16;
+#X obj 363 189 r \$0-blocksize;
+#X obj 204 186 r \$0-blocksize;
+#X obj 394 259 r \$0-blocksize;
+#X obj 390 123 s \$0-blocksize;
+#X text 34 13 VIRTUAL CIRCULAR BUFFER;
+#X text 34 23 =======================;
+#X obj 390 55 loadbang;
+#X msg 390 77 16;
+#X text 517 454 ---------------------------------;
+#X text 517 444 @krighxz / BELA / heavy / 12/2015;
+#X text 541 463 beaglert.cc / enzienaudio.com;
+#X text 426 78 << replace with target blocksize;
+#X text 446 90 BELA default: 16;
+#X text 446 102 PD default: 64;
+#X connect 0 0 20 0;
+#X connect 1 0 3 0;
+#X connect 2 0 3 1;
+#X connect 3 0 4 0;
+#X connect 4 0 5 0;
+#X connect 5 0 6 0;
+#X connect 5 0 9 0;
+#X connect 6 0 7 0;
+#X connect 6 0 4 1;
+#X connect 7 0 8 0;
+#X connect 9 0 10 0;
+#X connect 10 0 11 0;
+#X connect 11 0 12 1;
+#X connect 12 0 15 0;
+#X connect 13 0 14 1;
+#X connect 14 0 24 0;
+#X connect 15 0 16 0;
+#X connect 15 0 16 1;
+#X connect 18 0 8 0;
+#X connect 19 0 25 0;
+#X connect 20 0 1 0;
+#X connect 20 1 26 0;
+#X connect 20 2 13 0;
+#X connect 20 3 19 0;
+#X connect 24 0 12 0;
+#X connect 25 0 14 0;
+#X connect 26 0 2 0;
+#X connect 27 0 25 1;
+#X connect 28 0 26 1;
+#X connect 29 0 24 1;
+#X connect 33 0 34 0;
+#X connect 34 0 30 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/envelopeTrigger/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,196 @@
+#N canvas 646 209 359 287 10;
+#X obj 28 207 dac~;
+#N canvas 324 380 556 621 env 0;
+#N canvas 886 1001 131 207 >~ 0;
+#X obj 19 -37 -~;
+#X obj 19 -58 min~;
+#X obj 19 26 *~ 1e+37;
+#X obj 19 5 +~ 1e-37;
+#X obj 19 -16 clip~ -1e-37 0;
+#X obj 19 -83 inlet~;
+#X obj 62 -83 inlet~;
+#X obj 19 48 outlet~;
+#X connect 0 0 4 0;
+#X connect 1 0 0 0;
+#X connect 2 0 7 0;
+#X connect 3 0 2 0;
+#X connect 4 0 3 0;
+#X connect 5 0 1 0;
+#X connect 6 0 0 1;
+#X connect 6 0 1 1;
+#X restore 199 106 pd >~;
+#X obj 23 173 /~ 44100;
+#X obj 68 153 samplerate~;
+#X obj 68 133 loadbang;
+#X obj 199 128 biquad~ 0 0 -1 1 0;
+#X obj 23 209 rpole~;
+#X obj 23 153 sig~ 1;
+#X obj 226 171 sig~ 0.5;
+#N canvas 0 22 110 231 <~ 0;
+#X obj 11 -41 -~;
+#X obj 11 29 +~ 1e-37;
+#X obj 11 8 clip~ -1e-37 0;
+#X obj 11 -86 inlet~;
+#X obj 55 -85 inlet~;
+#X obj 11 -62 max~;
+#X obj 11 -17 *~ -1;
+#X obj 11 81 outlet~;
+#X obj 11 50 *~ 1e+37;
+#X connect 0 0 6 0;
+#X connect 1 0 8 0;
+#X connect 2 0 1 0;
+#X connect 3 0 5 0;
+#X connect 4 0 0 1;
+#X connect 4 0 5 1;
+#X connect 5 0 0 0;
+#X connect 6 0 2 0;
+#X connect 8 0 7 0;
+#X restore 199 192 pd <~;
+#X text 237 193 (x != x);
+#X obj 23 467 *~;
+#X obj 199 150 *~ -1;
+#X obj 23 331 *~ 512;
+#X obj 23 229 clip~ 0 1;
+#X obj 23 352 tabread4~ env1;
+#X obj 23 310 *~;
+#X obj 199 64 abs~;
+#X obj 199 43 hip~ 1;
+#X obj 199 22 inlet~ excitationSignal;
+#X obj 218 269 sig~ 1;
+#X obj 218 292 /~;
+#X obj 226 86 inlet~ threshold;
+#X obj 262 229 inlet~ envDuration;
+#X obj 38 445 osc~ 220;
+#X obj 38 425 +~ 50;
+#X obj 38 385 *~;
+#X obj 38 405 *~ 1000;
+#X obj 262 269 clip~ 1e-05 100000;
+#X obj 23 487 outlet~;
+#N canvas 0 22 450 278 (subpatch) 0;
+#X array env1 512 float 3;
+#A 0 0 0.0625 0.0883883 0.108253 0.125 0.139754 0.153093 0.165359 0.176777
+0.1875 0.197642 0.207289 0.216506 0.225347 0.233854 0.242061 0.25 0.257694
+0.265165 0.272431 0.279509 0.286411 0.293151 0.299739 0.306186 0.3125
+0.318689 0.32476 0.330719 0.336573 0.342327 0.347985 0.353553 0.359035
+0.364434 0.369755 0.375 0.380173 0.385276 0.390312 0.395285 0.400195
+0.405046 0.40984 0.414578 0.419263 0.423896 0.428478 0.433013 0.4375
+0.441942 0.446339 0.450694 0.455007 0.459279 0.463512 0.467707 0.471865
+0.475986 0.480072 0.484123 0.488141 0.492125 0.496078 0.5 0.503891
+0.507752 0.511585 0.515388 0.519164 0.522913 0.526634 0.53033 0.534
+0.537645 0.541266 0.544862 0.548435 0.551985 0.555512 0.559017 0.5625
+0.565962 0.569402 0.572822 0.576222 0.579601 0.582961 0.586302 0.589624
+0.592927 0.596212 0.599479 0.602728 0.60596 0.609175 0.612372 0.615554
+0.618718 0.621867 0.625 0.628117 0.631219 0.634306 0.637377 0.640434
+0.643477 0.646505 0.649519 0.652519 0.655506 0.658478 0.661438 0.664384
+0.667317 0.670238 0.673146 0.676041 0.678924 0.681795 0.684653 0.6875
+0.690335 0.693159 0.695971 0.698771 0.701561 0.704339 0.707107 0.709864
+0.71261 0.715345 0.71807 0.720785 0.72349 0.726184 0.728869 0.731544
+0.734209 0.736864 0.73951 0.742146 0.744773 0.747391 0.75 0.7526 0.75519
+0.757772 0.760345 0.76291 0.765466 0.768013 0.770552 0.773082 0.775605
+0.778119 0.780625 0.783123 0.785613 0.788095 0.790569 0.793036 0.795495
+0.797947 0.800391 0.802827 0.805256 0.807678 0.810093 0.8125 0.8149
+0.817294 0.81968 0.822059 0.824432 0.826797 0.829156 0.831508 0.833854
+0.836193 0.838525 0.840851 0.843171 0.845484 0.847791 0.850092 0.852386
+0.854675 0.856957 0.859233 0.861503 0.863767 0.866025 0.868278 0.870524
+0.872765 0.875 0.877229 0.879453 0.881671 0.883883 0.88609 0.888292
+0.890488 0.892679 0.894864 0.897044 0.899218 0.901388 0.903552 0.905711
+0.907865 0.910014 0.912157 0.914296 0.91643 0.918559 0.920682 0.922801
+0.924916 0.927025 0.929129 0.931229 0.933324 0.935414 0.9375 0.939581
+0.941657 0.943729 0.945797 0.947859 0.949918 0.951972 0.954021 0.956066
+0.958107 0.960143 0.962175 0.964203 0.966227 0.968246 0.970261 0.972272
+0.974279 0.976281 0.97828 0.980274 0.982265 0.984251 0.986233 0.988212
+0.990186 0.992157 0.994123 0.996086 0.998045 1 0.992172 0.984375 0.976609
+0.968874 0.961169 0.953495 0.945852 0.938239 0.930657 0.923106 0.915586
+0.908097 0.900638 0.89321 0.885813 0.878447 0.871111 0.863806 0.856532
+0.849289 0.842076 0.834894 0.827743 0.820623 0.813533 0.806474 0.799446
+0.792449 0.785483 0.778547 0.771642 0.764767 0.757924 0.751111 0.744329
+0.737578 0.730857 0.724168 0.717509 0.71088 0.704283 0.697716 0.69118
+0.684675 0.678201 0.671757 0.665344 0.658962 0.652611 0.64629 0.64
+0.633741 0.627513 0.621315 0.615148 0.609012 0.602907 0.596832 0.590788
+0.584775 0.578793 0.572841 0.56692 0.56103 0.555171 0.549343 0.543545
+0.537778 0.532041 0.526336 0.520661 0.515017 0.509404 0.503822 0.49827
+0.492749 0.487259 0.481799 0.476371 0.470973 0.465605 0.460269 0.454963
+0.449689 0.444444 0.439231 0.434048 0.428897 0.423775 0.418685 0.413625
+0.408597 0.403599 0.398631 0.393695 0.388789 0.383914 0.37907 0.374256
+0.369473 0.364721 0.36 0.355309 0.35065 0.346021 0.341423 0.336855
+0.332318 0.327812 0.323337 0.318893 0.314479 0.310096 0.305744 0.301423
+0.297132 0.292872 0.288643 0.284444 0.280277 0.27614 0.272034 0.267958
+0.263914 0.2599 0.255917 0.251965 0.248043 0.244152 0.240292 0.236463
+0.232664 0.228897 0.22516 0.221453 0.217778 0.214133 0.210519 0.206936
+0.203383 0.199862 0.196371 0.19291 0.189481 0.186082 0.182714 0.179377
+0.176071 0.172795 0.16955 0.166336 0.163153 0.16 0.156878 0.153787
+0.150727 0.147697 0.144698 0.14173 0.138793 0.135886 0.13301 0.130165
+0.127351 0.124567 0.121815 0.119093 0.116401 0.113741 0.111111 0.108512
+0.105944 0.103406 0.1009 0.0984237 0.0959785 0.093564 0.0911803 0.0888274
+0.0865052 0.0842138 0.0819531 0.0797232 0.077524 0.0753556 0.073218
+0.0711111 0.069035 0.0669896 0.064975 0.0629911 0.0610381 0.0591157
+0.0572241 0.0553633 0.0535332 0.0517339 0.0499654 0.0482276 0.0465206
+0.0448443 0.0431988 0.041584 0.04 0.0384467 0.0369243 0.0354325 0.0339715
+0.0325413 0.0311419 0.0297732 0.0284352 0.027128 0.0258516 0.0246059
+0.023391 0.0222068 0.0210534 0.0199308 0.0188389 0.0177778 0.0167474
+0.0157478 0.0147789 0.0138408 0.0129335 0.0120569 0.0112111 0.010396
+0.00961169 0.00885813 0.00813533 0.00744329 0.00678201 0.00615148 0.00555171
+0.0049827 0.00444444 0.00393695 0.00346021 0.00301423 0.002599 0.00221453
+0.00186082 0.00153787 0.00124567 0.000984237 0.000753556 0.000553633
+0.000384467 0.000246059 0.000138408 6.15148e-05 1.53787e-05 0;
+#X coords 0 1 512 0 512 64 1 0 0;
+#X restore 24 536 graph;
+#X text 244 55 centre signal around zero and take abs value;
+#X text 243 107 if greater than threshold output 1;
+#X text 313 129 differentiator;
+#X text 238 150 (generates impulse on positive trigger (0->1);
+#X text 67 210 signal-rate counter;
+#X text 296 193 -> resets counter by briefly setting;
+#X text 314 204 rpole~ coeff to 0;
+#X text 96 416 kickdrum 101 :P;
+#X text 400 514 pre-generated envelope;
+#X obj 262 249 *~;
+#X text 127 352 << use envelope value for volume and frequency;
+#X connect 0 0 4 0;
+#X connect 1 0 5 0;
+#X connect 2 0 1 1;
+#X connect 3 0 2 0;
+#X connect 4 0 11 0;
+#X connect 5 0 13 0;
+#X connect 6 0 1 0;
+#X connect 7 0 8 1;
+#X connect 8 0 5 1;
+#X connect 10 0 28 0;
+#X connect 11 0 8 0;
+#X connect 12 0 14 0;
+#X connect 13 0 15 0;
+#X connect 14 0 10 0;
+#X connect 14 0 25 0;
+#X connect 14 0 25 1;
+#X connect 15 0 12 0;
+#X connect 16 0 0 0;
+#X connect 17 0 16 0;
+#X connect 18 0 17 0;
+#X connect 19 0 20 0;
+#X connect 20 0 15 1;
+#X connect 21 0 0 1;
+#X connect 22 0 39 0;
+#X connect 22 0 39 1;
+#X connect 23 0 10 1;
+#X connect 24 0 23 0;
+#X connect 25 0 26 0;
+#X connect 26 0 24 0;
+#X connect 27 0 20 1;
+#X connect 39 0 27 0;
+#X restore 28 174 pd env;
+#X obj 79 110 adc~ 9;
+#X obj 129 130 adc~ 10;
+#X text 72 90 piezo input for excitation;
+#X text 123 110 fader 1 sets threshold;
+#X text 183 130 fader 2 sets duration;
+#X text 29 17 SAMPLE-ACCURATE ENVELOPE TRIGGER;
+#X text 29 27 ================================;
+#X obj 28 90 adc~ 8;
+#X text 141 236 ---------------------------------;
+#X text 141 226 @krighxz / BELA / heavy / 12/2015;
+#X text 165 245 beaglert.cc / enzienaudio.com;
+#X connect 1 0 0 0;
+#X connect 1 0 0 1;
+#X connect 2 0 1 1;
+#X connect 3 0 1 2;
+#X connect 9 0 1 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/hello-world/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,13 @@
+#N canvas 275 573 461 212 10;
+#X obj 39 143 dac~ 1 2;
+#X text 35 32 Hello world!;
+#X text 35 42 ============;
+#X text 95 79 (the sweet sound of success);
+#X obj 39 102 *~ 0.1;
+#X obj 39 81 osc~ 440;
+#X text 238 160 ---------------------------------;
+#X text 238 150 @krighxz / BELA / heavy / 12/2015;
+#X text 262 169 beaglert.cc / enzienaudio.com;
+#X connect 4 0 0 1;
+#X connect 4 0 0 0;
+#X connect 5 0 4 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/karplusStrong/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,240 @@
+#N canvas 440 516 715 490 10;
+#X obj 38 370 dac~ 1 2;
+#X text 470 442 ---------------------------------;
+#X text 470 432 @krighxz / BELA / heavy / 12/2015;
+#X text 494 451 beaglert.cc / enzienaudio.com;
+#X text 33 22 Karplus Strong;
+#X text 33 32 ==============;
+#X obj 38 323 vd~ \$0-wg1;
+#X obj 118 345 lop~ 1000;
+#X obj 118 367 *~ 0.99;
+#X obj 118 389 s~ \$0-fb1;
+#X obj 38 94 adc~ 3;
+#X obj 38 116 hip~ 100;
+#X obj 98 176 r~ \$0-fb1;
+#X obj 38 198 delwrite~ \$0-wg1 100;
+#X obj 38 268 *~;
+#X obj 38 290 *~ 10;
+#X text 99 116 <<< centre (i.e. DC block) signal with high-pass filter
+;
+#X text 100 94 <<< use accelerometer \, piezo or FSR on first analog
+in;
+#X text 105 245 <<< use potentiometer or fader on second analog in
+;
+#X text 100 75 EXCITATION INPUT:;
+#X text 100 225 DELAY PERIOD:;
+#X text 182 365 <<< and decay here [0-0.9999];
+#X text 182 345 <<< set damping here [~100-20000];
+#N canvas 335 566 461 274 gate 0;
+#N canvas 0 22 450 278 (subpatch) 0;
+#X array \$0-xfer 1024 float 3;
+#A 0 0 -0.808242 -0.804734 -0.801234 -0.797741 -0.794256 -0.790778
+-0.787309 -0.783846 -0.780392 -0.776945 -0.773506 -0.770074 -0.76665
+-0.763233 -0.759824 -0.756423 -0.75303 -0.749644 -0.746266 -0.742895
+-0.739532 -0.736176 -0.732829 -0.729488 -0.726156 -0.722831 -0.719514
+-0.716204 -0.712902 -0.709608 -0.706321 -0.703042 -0.69977 -0.696507
+-0.69325 -0.690002 -0.686761 -0.683527 -0.680302 -0.677084 -0.673873
+-0.67067 -0.667475 -0.664288 -0.661108 -0.657935 -0.654771 -0.651614
+-0.648464 -0.645323 -0.642188 -0.639062 -0.635943 -0.632832 -0.629728
+-0.626632 -0.623544 -0.620463 -0.61739 -0.614324 -0.611266 -0.608216
+-0.605174 -0.602139 -0.599111 -0.596092 -0.59308 -0.590075 -0.587078
+-0.584089 -0.581107 -0.578134 -0.575167 -0.572209 -0.569257 -0.566314
+-0.563378 -0.56045 -0.55753 -0.554617 -0.551711 -0.548814 -0.545924
+-0.543041 -0.540167 -0.537299 -0.53444 -0.531588 -0.528744 -0.525907
+-0.523078 -0.520257 -0.517443 -0.514637 -0.511839 -0.509048 -0.506265
+-0.503489 -0.500721 -0.497961 -0.495208 -0.492463 -0.489726 -0.486996
+-0.484274 -0.481559 -0.478852 -0.476153 -0.473461 -0.470777 -0.468101
+-0.465432 -0.462771 -0.460117 -0.457472 -0.454833 -0.452203 -0.44958
+-0.446964 -0.444357 -0.441757 -0.439164 -0.436579 -0.434002 -0.431432
+-0.42887 -0.426316 -0.42377 -0.42123 -0.418699 -0.416175 -0.413659
+-0.41115 -0.40865 -0.406156 -0.403671 -0.401193 -0.398722 -0.396259
+-0.393804 -0.391357 -0.388917 -0.386485 -0.38406 -0.381643 -0.379234
+-0.376832 -0.374438 -0.372051 -0.369673 -0.367301 -0.364938 -0.362582
+-0.360233 -0.357893 -0.35556 -0.353234 -0.350916 -0.348606 -0.346304
+-0.344009 -0.341721 -0.339442 -0.33717 -0.334905 -0.332649 -0.330399
+-0.328158 -0.325924 -0.323698 -0.321479 -0.319268 -0.317065 -0.314869
+-0.312681 -0.3105 -0.308328 -0.306162 -0.304005 -0.301855 -0.299713
+-0.297578 -0.295451 -0.293331 -0.291219 -0.289115 -0.287019 -0.28493
+-0.282848 -0.280775 -0.278709 -0.27665 -0.2746 -0.272556 -0.270521
+-0.268493 -0.266473 -0.26446 -0.262455 -0.260458 -0.258468 -0.256486
+-0.254511 -0.252545 -0.250585 -0.248634 -0.24669 -0.244753 -0.242825
+-0.240904 -0.23899 -0.237084 -0.235186 -0.233296 -0.231413 -0.229537
+-0.22767 -0.22581 -0.223957 -0.222112 -0.220275 -0.218446 -0.216624
+-0.21481 -0.213003 -0.211204 -0.209413 -0.207629 -0.205853 -0.204084
+-0.202323 -0.20057 -0.198824 -0.197086 -0.195356 -0.193633 -0.191918
+-0.190211 -0.188511 -0.186819 -0.185134 -0.183457 -0.181788 -0.180126
+-0.178472 -0.176826 -0.175187 -0.173556 -0.171932 -0.170316 -0.168708
+-0.167108 -0.165515 -0.163929 -0.162351 -0.160781 -0.159219 -0.157664
+-0.156117 -0.154577 -0.153045 -0.151521 -0.150004 -0.148495 -0.146993
+-0.1455 -0.144013 -0.142535 -0.141064 -0.139601 -0.138145 -0.136697
+-0.135256 -0.133824 -0.132398 -0.130981 -0.129571 -0.128169 -0.126774
+-0.125387 -0.124008 -0.122636 -0.121272 -0.119915 -0.118566 -0.117225
+-0.115891 -0.114565 -0.113247 -0.111936 -0.110633 -0.109338 -0.10805
+-0.10677 -0.105497 -0.104232 -0.102975 -0.101725 -0.100483 -0.0992487
+-0.0980219 -0.0968027 -0.0955911 -0.0943872 -0.0931909 -0.0920023 -0.0908212
+-0.0896478 -0.0884821 -0.0873239 -0.0861734 -0.0850305 -0.0838953 -0.0827676
+-0.0816476 -0.0805353 -0.0794305 -0.0783334 -0.077244 -0.0761621 -0.0750879
+-0.0740213 -0.0729623 -0.071911 -0.0708673 -0.0698312 -0.0688028 -0.067782
+-0.0667688 -0.0657632 -0.0647653 -0.063775 -0.0627924 -0.0618173 -0.0608499
+-0.0598901 -0.058938 -0.0579935 -0.0570566 -0.0561273 -0.0552057 -0.0542917
+-0.0533853 -0.0524866 -0.0515955 -0.050712 -0.0498361 -0.0489679 -0.0481073
+-0.0472543 -0.046409 -0.0455713 -0.0447412 -0.0439188 -0.0431039 -0.0422968
+-0.0414972 -0.0407053 -0.039921 -0.0391443 -0.0383752 -0.0376138 -0.03686
+-0.0361139 -0.0353754 -0.0346445 -0.0339212 -0.0332056 -0.0324976 -0.0317972
+-0.0311044 -0.0304193 -0.0297418 -0.029072 -0.0284097 -0.0277551 -0.0271082
+-0.0264688 -0.0258371 -0.025213 -0.0245966 -0.0239877 -0.0233865 -0.022793
+-0.022207 -0.0216287 -0.021058 -0.020495 -0.0199396 -0.0193918 -0.0188516
+-0.0183191 -0.0177942 -0.0172769 -0.0167673 -0.0162653 -0.0157709 -0.0152841
+-0.014805 -0.0143335 -0.0138696 -0.0134134 -0.0129648 -0.0125238 -0.0120905
+-0.0116647 -0.0112466 -0.0108362 -0.0104333 -0.0100381 -0.00965057
+-0.00927063 -0.00889832 -0.00853363 -0.00817657 -0.00782715 -0.00748535
+-0.00715118 -0.00682465 -0.00650574 -0.00619446 -0.00589081 -0.00559479
+-0.0053064 -0.00502563 -0.0047525 -0.004487 -0.00422913 -0.00397888
+-0.00373627 -0.00350128 -0.00327393 -0.0030542 -0.0028421 -0.00263763
+-0.0024408 -0.00225159 -0.00207001 -0.00189606 -0.00172974 -0.00157104
+-0.00141998 -0.00127655 -0.00114075 -0.00101257 -0.000892029 -0.000779114
+-0.000673828 -0.000576172 -0.000486145 -0.000403747 -0.000328979 -0.000261841
+-0.000202332 -0.000150452 -0.000106201 -6.95801e-05 -4.05884e-05 -1.92261e-05
+-5.49316e-06 0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0
+-0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0 -0
+-0 -0 -0 -0 -0 -0 -0 -0 -0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0
+0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5.49316e-06
+1.92261e-05 4.05884e-05 6.95801e-05 0.000106201 0.000150452 0.000202332
+0.000261841 0.000328979 0.000403747 0.000486145 0.000576172 0.000673828
+0.000779114 0.000892029 0.00101257 0.00114075 0.00127655 0.00141998
+0.00157104 0.00172974 0.00189606 0.00207001 0.00225159 0.0024408 0.00263763
+0.0028421 0.0030542 0.00327393 0.00350128 0.00373627 0.00397888 0.00422913
+0.004487 0.0047525 0.00502563 0.0053064 0.00559479 0.00589081 0.00619446
+0.00650574 0.00682465 0.00715118 0.00748535 0.00782715 0.00817657 0.00853363
+0.00889832 0.00927063 0.00965057 0.0100381 0.0104333 0.0108362 0.0112466
+0.0116647 0.0120905 0.0125238 0.0129648 0.0134134 0.0138696 0.0143335
+0.014805 0.0152841 0.0157709 0.0162653 0.0167673 0.0172769 0.0177942
+0.0183191 0.0188516 0.0193918 0.0199396 0.020495 0.021058 0.0216287
+0.022207 0.022793 0.0233865 0.0239877 0.0245966 0.025213 0.0258371
+0.0264688 0.0271082 0.0277551 0.0284097 0.029072 0.0297418 0.0304193
+0.0311044 0.0317972 0.0324976 0.0332056 0.0339212 0.0346445 0.0353754
+0.0361139 0.03686 0.0376138 0.0383752 0.0391443 0.039921 0.0407053
+0.0414972 0.0422968 0.0431039 0.0439188 0.0447412 0.0455713 0.046409
+0.0472543 0.0481073 0.0489679 0.0498361 0.050712 0.0515955 0.0524866
+0.0533853 0.0542917 0.0552057 0.0561273 0.0570566 0.0579935 0.058938
+0.0598901 0.0608499 0.0618173 0.0627924 0.063775 0.0647653 0.0657632
+0.0667688 0.067782 0.0688028 0.0698312 0.0708673 0.071911 0.0729623
+0.0740213 0.0750879 0.0761621 0.077244 0.0783334 0.0794305 0.0805353
+0.0816476 0.0827676 0.0838953 0.0850305 0.0861734 0.0873239 0.0884821
+0.0896478 0.0908212 0.0920023 0.0931909 0.0943872 0.0955911 0.0968027
+0.0980219 0.0992487 0.100483 0.101725 0.102975 0.104232 0.105497 0.10677
+0.10805 0.109338 0.110633 0.111936 0.113247 0.114565 0.115891 0.117225
+0.118566 0.119915 0.121272 0.122636 0.124008 0.125387 0.126774 0.128169
+0.129571 0.130981 0.132398 0.133824 0.135256 0.136697 0.138145 0.139601
+0.141064 0.142535 0.144013 0.1455 0.146993 0.148495 0.150004 0.151521
+0.153045 0.154577 0.156117 0.157664 0.159219 0.160781 0.162351 0.163929
+0.165515 0.167108 0.168708 0.170316 0.171932 0.173556 0.175187 0.176826
+0.178472 0.180126 0.181788 0.183457 0.185134 0.186819 0.188511 0.190211
+0.191918 0.193633 0.195356 0.197086 0.198824 0.20057 0.202323 0.204084
+0.205853 0.207629 0.209413 0.211204 0.213003 0.21481 0.216624 0.218446
+0.220275 0.222112 0.223957 0.22581 0.22767 0.229537 0.231413 0.233296
+0.235186 0.237084 0.23899 0.240904 0.242825 0.244753 0.24669 0.248634
+0.250585 0.252545 0.254511 0.256486 0.258468 0.260458 0.262455 0.26446
+0.266473 0.268493 0.270521 0.272556 0.2746 0.27665 0.278709 0.280775
+0.282848 0.28493 0.287019 0.289115 0.291219 0.293331 0.295451 0.297578
+0.299713 0.301855 0.304005 0.306162 0.308328 0.3105 0.312681 0.314869
+0.317065 0.319268 0.321479 0.323698 0.325924 0.328158 0.330399 0.332649
+0.334905 0.33717 0.339442 0.341721 0.344009 0.346304 0.348606 0.350916
+0.353234 0.35556 0.357893 0.360233 0.362582 0.364938 0.367301 0.369673
+0.372051 0.374438 0.376832 0.379234 0.381643 0.38406 0.386485 0.388917
+0.391357 0.393804 0.396259 0.398722 0.401193 0.403671 0.406156 0.40865
+0.41115 0.413659 0.416175 0.418699 0.42123 0.42377 0.426316 0.42887
+0.431432 0.434002 0.436579 0.439164 0.441757 0.444357 0.446964 0.44958
+0.452203 0.454833 0.457472 0.460117 0.462771 0.465432 0.468101 0.470777
+0.473461 0.476153 0.478852 0.481559 0.484274 0.486996 0.489726 0.492463
+0.495208 0.497961 0.500721 0.503489 0.506265 0.509048 0.511839 0.514637
+0.517443 0.520257 0.523078 0.525907 0.528744 0.531588 0.53444 0.537299
+0.540167 0.543041 0.545924 0.548814 0.551711 0.554617 0.55753 0.56045
+0.563378 0.566314 0.569257 0.572209 0.575167 0.578134 0.581107 0.584089
+0.587078 0.590075 0.59308 0.596092 0.599111 0.602139 0.605174 0.608216
+0.611266 0.614324 0.61739 0.620463 0.623544 0.626632 0.629728 0.632832
+0.635943 0.639062 0.642188 0.645323 0.648464 0.651614 0.654771 0.657935
+0.661108 0.664288 0.667475 0.67067 0.673873 0.677084 0.680302 0.683527
+0.686761 0.690002 0.69325 0.696507 0.69977 0.703042 0.706321 0.709608
+0.712902 0.716204 0.719514 0.722831;
+#A 1000 0.726156 0.729488 0.732829 0.736176 0.739532 0.742895 0.746266
+0.749644 0.75303 0.756423 0.759824 0.763233 0.76665 0.770074 0.773506
+0.776945 0.780392 0.783846 0.787309 0.790778 0.794256 0.797741 0.801234
+0.804734;
+#X coords 0 1 1023 -1 200 200 1 0 0;
+#X restore 230 34 graph;
+#X obj 25 27 inlet~;
+#X obj 25 49 clip~ -1 1;
+#X obj 25 71 *~ 512;
+#X obj 25 93 +~ 512;
+#X obj 25 115 tabread4~ \$0-xfer;
+#X obj 25 137 outlet~;
+#N canvas 0 22 334 332 generate-xfer 0;
+#X obj 8 290 tabwrite \$0-xfer;
+#X obj 8 109 / 1024;
+#X obj 8 129 * 2;
+#X obj 8 149 - 1;
+#X obj 8 169 moses 0;
+#X obj 8 191 + 0.1;
+#X obj 8 213 clip -1 0;
+#X obj 68 191 - 0.1;
+#X obj 68 213 clip 0 1;
+#X obj 101 16 inlet threshold;
+#X obj 101 78 count 1024;
+#X obj 128 58 s \$0-thresh;
+#X obj 95 169 r \$0-thresh;
+#X obj 101 38 t b f;
+#X obj 68 236 *;
+#X obj 8 236 *;
+#X obj 8 258 * -1;
+#X text 140 203 <<< deadzone;
+#X text 140 253 <<< smooth by taking exponent;
+#X connect 1 0 2 0;
+#X connect 2 0 3 0;
+#X connect 3 0 4 0;
+#X connect 4 0 5 0;
+#X connect 4 1 7 0;
+#X connect 5 0 6 0;
+#X connect 6 0 15 0;
+#X connect 6 0 15 1;
+#X connect 7 0 8 0;
+#X connect 8 0 14 0;
+#X connect 8 0 14 1;
+#X connect 9 0 13 0;
+#X connect 10 0 0 1;
+#X connect 10 0 1 0;
+#X connect 12 0 5 1;
+#X connect 12 0 7 1;
+#X connect 13 0 10 0;
+#X connect 13 1 11 0;
+#X connect 14 0 0 0;
+#X connect 15 0 16 0;
+#X connect 16 0 0 0;
+#X restore 26 217 pd generate-xfer;
+#X text 58 196 <<< threshold;
+#X obj 26 173 loadbang;
+#X msg 26 195 0.1;
+#X connect 1 0 2 0;
+#X connect 2 0 3 0;
+#X connect 3 0 4 0;
+#X connect 4 0 5 0;
+#X connect 5 0 6 0;
+#X connect 9 0 10 0;
+#X connect 10 0 7 0;
+#X restore 38 137 pd gate;
+#X obj 38 246 adc~ 10;
+#X text 98 137 <<< thresholding to remove any consistent noise in the
+excitation signal;
+#X connect 6 0 7 0;
+#X connect 6 0 0 0;
+#X connect 6 0 0 1;
+#X connect 7 0 8 0;
+#X connect 8 0 9 0;
+#X connect 10 0 11 0;
+#X connect 11 0 23 0;
+#X connect 12 0 13 0;
+#X connect 14 0 15 0;
+#X connect 15 0 6 0;
+#X connect 23 0 13 0;
+#X connect 24 0 14 0;
+#X connect 24 0 14 1;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/karplusStrong/count.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,30 @@
+#N canvas 592 177 306 227 10;
+#X obj 32 111 f;
+#X obj 57 111 + 1;
+#X obj 57 151 sel 0;
+#X obj 57 171 del 1e-36;
+#X obj 57 131 > 1023;
+#X msg 32 90 0;
+#X obj 19 171 - 1;
+#X obj 19 193 outlet;
+#X obj 90 87 \$1;
+#X obj 90 109 - 1;
+#X obj 90 66 loadbang;
+#X obj 32 48 inlet;
+#X obj 32 69 t b;
+#X text 33 14 temporary replacement for [until] object;
+#X text 67 195 outputs index (0->[N-1]);
+#X connect 0 0 1 0;
+#X connect 1 0 0 1;
+#X connect 1 0 4 0;
+#X connect 1 0 6 0;
+#X connect 2 0 3 0;
+#X connect 3 0 0 0;
+#X connect 4 0 2 0;
+#X connect 5 0 0 0;
+#X connect 6 0 7 0;
+#X connect 8 0 9 0;
+#X connect 9 0 4 1;
+#X connect 10 0 8 0;
+#X connect 11 0 12 0;
+#X connect 12 0 5 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/rubberDuckie/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,247 @@
+#N canvas 275 573 442 207 10;
+#X obj 39 149 dac~ 1 2;
+#X text 218 143 ---------------------------------;
+#X text 218 133 @krighxz / BELA / heavy / 12/2015;
+#X text 242 152 beaglert.cc / enzienaudio.com;
+#X text 35 32 Rubber Duckie;
+#X text 35 42 =============;
+#N canvas 325 86 823 605 duckie 0;
+#X obj 186 510 *~;
+#X obj 306 517 *~;
+#X obj 372 468 noise~;
+#X obj 372 492 bp~ 3000 10;
+#X obj 366 162 abs~;
+#X obj 509 158 sig~ 0;
+#X obj 467 371 +~;
+#X obj 411 210 -~ 0.55;
+#X obj 411 231 /~ 0.2;
+#X obj 411 252 clip~ 0 1;
+#X obj 411 282 *~;
+#X obj 411 308 *~ 1000;
+#X obj 366 334 +~;
+#X obj 366 308 +~ 800;
+#X obj 186 536 *~ 0.2;
+#X obj 366 282 *~ 800;
+#N canvas 568 775 135 226 <~ 0;
+#X obj 20 -43 -~;
+#X obj 20 27 +~ 1e-37;
+#X obj 20 6 clip~ -1e-37 0;
+#X obj 20 -88 inlet~;
+#X obj 64 -87 inlet~;
+#X obj 20 -64 max~;
+#X obj 20 -19 *~ -1;
+#X obj 20 79 outlet~;
+#X obj 20 48 *~ 1e+37;
+#X connect 0 0 6 0;
+#X connect 1 0 8 0;
+#X connect 2 0 1 0;
+#X connect 3 0 5 0;
+#X connect 4 0 0 1;
+#X connect 4 0 5 1;
+#X connect 5 0 0 0;
+#X connect 6 0 2 0;
+#X connect 8 0 7 0;
+#X restore 186 367 pd <~ 0;
+#N canvas 568 775 135 226 <~ 0;
+#X obj 20 -43 -~;
+#X obj 20 27 +~ 1e-37;
+#X obj 20 6 clip~ -1e-37 0;
+#X obj 20 -88 inlet~;
+#X obj 64 -87 inlet~;
+#X obj 20 -64 max~;
+#X obj 20 -19 *~ -1;
+#X obj 20 79 outlet~;
+#X obj 20 48 *~ 1e+37;
+#X connect 0 0 6 0;
+#X connect 1 0 8 0;
+#X connect 2 0 1 0;
+#X connect 3 0 5 0;
+#X connect 4 0 0 1;
+#X connect 4 0 5 1;
+#X connect 5 0 0 0;
+#X connect 6 0 2 0;
+#X connect 8 0 7 0;
+#X restore 482 181 pd <~;
+#X obj 186 428 *~;
+#X obj 225 345 sig~ 1;
+#X obj 186 394 lop~ 10;
+#X text 524 393 << band-limited pulse;
+#X text 10 367 reed stops when overblown >>;
+#X obj 186 460 *~;
+#X obj 186 480 *~;
+#X text 25 470 exp amplitude response >>;
+#X text 537 238 << detune frequency on change of direction;
+#X obj 482 236 *~ -300;
+#X obj 306 485 *~;
+#X obj 306 449 *~ 0.1;
+#X text 448 493 << noise simulates non-oscillating airflow when overblown
+;
+#X obj 186 561 outlet~;
+#N canvas 58 1286 407 525 pulse 0;
+#X obj 83 340 *~;
+#X obj 83 366 *~;
+#X obj 31 366 sig~ 1;
+#X obj 52 419 /~;
+#X obj 67 393 +~;
+#X text 116 366 X^2;
+#X text 97 396 1+X^2;
+#X text 84 421 1/(1+X^2);
+#X obj 83 317 osc~;
+#X obj 167 320 clip~ 0 999999;
+#X obj 52 483 outlet~;
+#X text 271 218 << tweak all this;
+#X text 25 14 based on F04.waveshaping.pulse.pd;
+#X obj 83 84 /~ 2;
+#X obj 167 148 -~;
+#X obj 167 170 /~ 127;
+#X obj 52 452 hip~ 5;
+#X obj 167 202 *~;
+#X obj 167 232 *~;
+#X obj 167 262 *~;
+#X obj 167 294 *~ 1000;
+#X obj 118 125 sig~ 139;
+#X obj 83 58 inlet~;
+#N canvas 331 1377 215 174 _ftom 0;
+#X obj -482 -776 tabread4~ _ftom;
+#X obj -482 -818 /~ 10000;
+#X obj -482 -797 *~ 256;
+#N canvas 0 23 450 278 (subpatch) 0;
+#X array _ftom 256 float 3;
+#A 0 0 27.0762 39.0762 46.0958 51.0762 54.9394 58.0958 60.7645 63.0762
+65.1153 66.9394 68.5894 70.0958 71.4815 72.7645 73.9589 75.0762 76.1258
+77.1153 78.0514 78.9394 79.784 80.5894 81.359 82.0958 82.8025 83.4815
+84.1349 84.7645 85.372 85.9589 86.5266 87.0762 87.609 88.1258 88.6276
+89.1153 89.5897 90.0514 90.5011 90.9394 91.3669 91.784 92.1914 92.5894
+92.9785 93.359 93.7313 94.0958 94.4528 94.8025 95.1453 95.4815 95.8113
+96.1349 96.4525 96.7645 97.0709 97.372 97.6679 97.9589 98.2451 98.5266
+98.8036 99.0762 99.3446 99.609 99.8693 100.126 100.379 100.628 100.873
+101.115 101.354 101.59 101.822 102.051 102.278 102.501 102.722 102.939
+103.154 103.367 103.577 103.784 103.989 104.191 104.392 104.589 104.785
+104.978 105.17 105.359 105.546 105.731 105.914 106.096 106.275 106.453
+106.629 106.803 106.975 107.145 107.314 107.482 107.647 107.811 107.974
+108.135 108.294 108.453 108.609 108.764 108.918 109.071 109.222 109.372
+109.521 109.668 109.814 109.959 110.103 110.245 110.386 110.527 110.666
+110.804 110.94 111.076 111.211 111.345 111.477 111.609 111.74 111.869
+111.998 112.126 112.253 112.379 112.504 112.628 112.751 112.873 112.995
+113.115 113.235 113.354 113.472 113.59 113.706 113.822 113.937 114.051
+114.165 114.278 114.39 114.501 114.612 114.722 114.831 114.939 115.047
+115.154 115.261 115.367 115.472 115.577 115.681 115.784 115.887 115.989
+116.09 116.191 116.292 116.392 116.491 116.589 116.688 116.785 116.882
+116.978 117.074 117.17 117.265 117.359 117.453 117.546 117.639 117.731
+117.823 117.915 118.005 118.096 118.186 118.275 118.364 118.453 118.541
+118.629 118.716 118.803 118.889 118.975 119.06 119.145 119.23 119.314
+119.398 119.482 119.565 119.647 119.729 119.811 119.893 119.974 120.055
+120.135 120.215 120.294 120.374 120.453 120.531 120.609 120.687 120.764
+120.842 120.918 120.995 121.071 121.147 121.222 121.297 121.372 121.446
+121.521 121.594 121.668 121.741 121.814 121.887 121.959 122.031 122.103
+122.174 122.245 122.316 122.386 122.457 122.527 122.596 122.666 122.735
+122.804 122.872 122.94 123.008;
+#X coords 0 127 256 -12 50 50 1 0 0;
+#X restore -546 -793 graph;
+#X obj -482 -838 clip~ 0 10000;
+#X obj -482 -858 inlet~;
+#X obj -482 -755 outlet~;
+#X text -567 -722 shoddy temp replacement for ftom~;
+#X connect 0 0 6 0;
+#X connect 1 0 2 0;
+#X connect 2 0 0 0;
+#X connect 4 0 1 0;
+#X connect 5 0 4 0;
+#X restore 182 125 pd _ftom;
+#X connect 0 0 1 0;
+#X connect 0 0 1 1;
+#X connect 1 0 4 1;
+#X connect 2 0 3 0;
+#X connect 2 0 4 0;
+#X connect 3 0 16 0;
+#X connect 4 0 3 1;
+#X connect 8 0 0 0;
+#X connect 9 0 0 1;
+#X connect 13 0 8 0;
+#X connect 13 0 23 0;
+#X connect 14 0 15 0;
+#X connect 15 0 17 0;
+#X connect 15 0 17 1;
+#X connect 16 0 10 0;
+#X connect 17 0 18 0;
+#X connect 17 0 18 1;
+#X connect 18 0 19 0;
+#X connect 18 0 19 1;
+#X connect 19 0 20 0;
+#X connect 20 0 9 0;
+#X connect 21 0 14 0;
+#X connect 22 0 13 0;
+#X connect 23 0 14 1;
+#X restore 467 394 pd pulse;
+#X obj 366 105 inlet~;
+#X text 295 104 airflow >>;
+#X text 218 118 ('squeeze pressure');
+#X text 13 20 Sound model of a rubber duckie toy;
+#X text 14 51 Hint: use the differential of a continuous signal as
+input for a realistic response;
+#X text 13 29 ==================================;
+#X obj 366 133 lop~ 0.5;
+#X text 423 132 << airflow resistance;
+#X connect 0 0 14 0;
+#X connect 1 0 14 0;
+#X connect 2 0 3 0;
+#X connect 3 0 1 1;
+#X connect 4 0 7 0;
+#X connect 4 0 15 0;
+#X connect 4 0 29 0;
+#X connect 4 0 18 1;
+#X connect 4 0 16 0;
+#X connect 5 0 17 1;
+#X connect 6 0 32 0;
+#X connect 7 0 8 0;
+#X connect 8 0 9 0;
+#X connect 9 0 10 0;
+#X connect 9 0 10 1;
+#X connect 10 0 11 0;
+#X connect 11 0 12 1;
+#X connect 12 0 6 0;
+#X connect 13 0 12 0;
+#X connect 14 0 31 0;
+#X connect 15 0 13 0;
+#X connect 16 0 20 0;
+#X connect 17 0 27 0;
+#X connect 18 0 23 0;
+#X connect 18 0 23 1;
+#X connect 19 0 16 1;
+#X connect 20 0 18 0;
+#X connect 23 0 24 1;
+#X connect 23 0 24 0;
+#X connect 24 0 0 0;
+#X connect 27 0 6 1;
+#X connect 28 0 1 0;
+#X connect 29 0 28 1;
+#X connect 29 0 28 0;
+#X connect 32 0 0 1;
+#X connect 33 0 39 0;
+#X connect 39 0 4 0;
+#X connect 39 0 17 0;
+#X restore 39 127 pd duckie;
+#X obj 39 77 adc~ 10;
+#N canvas 0 22 504 229 differential 0;
+#X obj 27 80 rzero~ 1;
+#X obj 72 57 sig~ 1;
+#X obj 27 152 *~ 44100;
+#X obj 72 131 samplerate~;
+#X obj 72 110 loadbang;
+#X obj 27 25 inlet~;
+#X obj 27 190 outlet~;
+#X text 84 83 y[n] = x[n] - x[n-1];
+#X text 121 57 <<< heavy currently requires signal input to set coefficient
+;
+#X text 91 151 <<< multiply by samplerate to get velocity;
+#X connect 0 0 2 0;
+#X connect 1 0 0 1;
+#X connect 2 0 6 0;
+#X connect 3 0 2 1;
+#X connect 4 0 3 0;
+#X connect 5 0 0 0;
+#X restore 39 101 pd differential;
+#X connect 6 0 0 0;
+#X connect 6 0 0 1;
+#X connect 7 0 8 0;
+#X connect 8 0 6 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/samphold/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,22 @@
+#N canvas 275 504 414 247 10;
+#X obj 55 212 dac~ 1 2;
+#X obj 55 171 *~ 0.1;
+#X obj 55 150 osc~ 440;
+#X obj 55 61 noise~;
+#X obj 55 128 samphold~;
+#X text 51 21 ==================;
+#X text 51 11 Sample and hold FM;
+#X obj 55 85 lop~ 1;
+#X obj 122 107 phasor~ 880;
+#X obj 55 107 *~ 1e+06;
+#X text 193 199 ---------------------------------;
+#X text 193 189 @krighxz / BELA / heavy / 12/2015;
+#X text 217 208 beaglert.cc / enzienaudio.com;
+#X connect 1 0 0 1;
+#X connect 1 0 0 0;
+#X connect 2 0 1 0;
+#X connect 3 0 7 0;
+#X connect 4 0 2 0;
+#X connect 7 0 9 0;
+#X connect 8 0 4 1;
+#X connect 9 0 4 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/simple-fm/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,42 @@
+#N canvas 275 573 409 282 10;
+#X obj 37 230 dac~ 1 2;
+#X text 175 222 ---------------------------------;
+#X obj 37 102 *~ 1000;
+#X obj 37 199 *~ 0.1;
+#X obj 37 79 adc~ 3;
+#X obj 65 125 adc~ 4;
+#X obj 94 147 adc~ 5;
+#N canvas 81 574 322 252 FMvoice 1;
+#X obj 20 174 +~;
+#X obj 93 116 osc~;
+#X obj 93 157 *~;
+#X obj 93 76 *~;
+#X obj 158 98 *~;
+#X obj 20 225 outlet~;
+#X obj 20 200 osc~;
+#X obj 20 39 inlet~ freq;
+#X obj 108 39 inlet~ harmRatio~;
+#X obj 173 69 inlet~ modIndex~;
+#X connect 0 0 6 0;
+#X connect 1 0 2 0;
+#X connect 2 0 0 1;
+#X connect 3 0 4 0;
+#X connect 3 0 1 0;
+#X connect 4 0 2 1;
+#X connect 6 0 5 0;
+#X connect 7 0 3 0;
+#X connect 7 0 0 0;
+#X connect 8 0 3 1;
+#X connect 9 0 4 1;
+#X restore 37 169 pd FMvoice;
+#X text 33 22 Simple FM;
+#X text 33 32 =========;
+#X text 175 212 @krighxz / BELA / heavy / 12/2015;
+#X text 199 231 beaglert.cc / enzienaudio.com;
+#X connect 2 0 7 0;
+#X connect 3 0 0 1;
+#X connect 3 0 0 0;
+#X connect 4 0 2 0;
+#X connect 5 0 7 1;
+#X connect 6 0 7 2;
+#X connect 7 0 3 0;
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/projects/heavy/pd/tableScrubbing/_main.pd	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,35 @@
+#N canvas 503 319 861 473 10;
+#N canvas 0 22 450 278 (subpatch) 0;
+#X array exampleTable 65238 float 2;
+#X coords 0 1 65238 -1 200 140 1 0 0;
+#X restore 21 213 graph;
+#X obj 243 329 adc~ 1 2 3;
+#X obj 300 426 dac~;
+#X text 317 264 <<< delete this object before compiling!;
+#X obj 300 392 tabread4~ exampleTable;
+#X msg 243 218 read -resize rt.wav exampleTable;
+#X obj 300 350 lop~ 1;
+#X obj 300 371 *~ 65238;
+#X obj 243 266 soundfiler;
+#X text 489 229 right-click array -> properties -> toggle "save contents"
+;
+#X text 463 216 <<< after loading a file:;
+#X text 17 23 Load sample into table and scrub using analog input;
+#X text 17 33 ===================================================;
+#X text 362 351 <<< avoid zipper noise;
+#X text 362 371 <<< length of sample;
+#X text 317 328 <<< analog input 0 (range 0-1);
+#X text 631 419 ---------------------------------;
+#X text 631 409 @krighxz / BELA / heavy / 12/2015;
+#X text 655 428 beaglert.cc / enzienaudio.com;
+#X text 30 61 N.B. the patch cannot be bigger than 512kb in size \;
+only use this for *very small soundfiles*;
+#X text 29 99 You can modify the render.cpp file to load samples into
+tables using the Heavy API: https://enzienaudio.com/docs/c.html#api-hv-table
+;
+#X connect 1 2 6 0;
+#X connect 4 0 2 0;
+#X connect 4 0 2 1;
+#X connect 5 0 8 0;
+#X connect 6 0 7 0;
+#X connect 7 0 4 0;
Binary file projects/heavy/pd/tableScrubbing/rt.wav has changed
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/scripts/build_pd.sh	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,110 @@
+#!/bin/bash
+
+# shell script for automatic uploading/compiling of pd patch onto bbb
+# Christian Heinrichs 2015
+#
+# example usage: sh upload-and-compile.sh -f bwg-tests -q -e
+
+workingdir=".."
+verbose="0"
+render="0"
+pdpath=""
+projectpath="../projects/heavy/hvtemp"
+BBB_PATH="~/BeagleRT"
+BBB_ADDRESS="root@192.168.7.2"
+COMMAND_ARGS=
+RUN_PROJECT=1
+RUN_IN_FOREGROUND=0
+RUN_WITHOUT_SCREEN=1
+
+function usage
+{
+    echo "
+    USAGE: build_pd.sh [[-i input folder containing _main.pd file ] [-o output folder for new heavy project .c files (default ../projects/heavy/hvtemp)] [-b bbb path to copy to (default ~/BeagleRT)] | [-h]]
+    "    
+    echo "example: build_pd.sh -i ../projects/heavy/pd/hello-world -o ../projects/heavy/hello-world"
+}
+
+while [ "$1" != "" ]; do
+    case $1 in
+        -b | --bbb )            shift
+                                BBB_PATH=$1
+                                ;;
+        -i | --input )          shift
+                                pdpath=$1
+                                ;;
+        -o | --output )         shift
+                                projectpath=$1
+                                ;;
+        -v | --verbose )        shift
+                                verbose=1
+                                ;;
+        -r | --render )         shift
+                                render=1
+                                ;;
+        -h | --help )           usage
+                                exit
+                                ;;
+        * )                     usage
+                                exit 1
+    esac
+    shift
+done
+
+/usr/bin/python hvresources/uploader.py "$pdpath"/ -n bbb -g c -o "$projectpath"/;
+if [ $? -ne 0 ]; then
+    /usr/local/bin/python hvresources/uploader.py "$pdpath"/ -n bbb -g c -o "$projectpath"/;
+    if [ $? -ne 0 ]; then
+        #echo "ERROR: an error occurred while executing the uploader.py script"
+        echo "error"
+        exit 1
+    fi;
+fi;
+echo "";
+#echo "*|*|* Successfully uploaded and converted pd patch into super-fast optimized C code. Brought to you by Heavy! *|*|*";
+echo "";
+
+# check how to copy/sync render.cpp file...
+if [ $render -eq 0 ]; then
+    rsync "hvresources/render.cpp" $projectpath/ --ignore-existing;
+fi;
+
+rsync -c -r "$projectpath"/ "$BBB_ADDRESS":"$BBB_PATH"/source;
+
+if [ $? -ne 0 ]; then
+    echo "";
+    echo ":( :( :( ERROR: while synchronizing files with the BBB. Is the board connected and the correct SD card inserted? :( :( :(";
+    echo "";
+    exit 1;
+fi;
+
+# remove old executable and heavy context .o/.d files
+ssh $BBB_ADDRESS "rm $BBB_PATH/BeagleRT $BBB_PATH/build/source/HvContext_bbb.d $BBB_PATH/build/source/HvContext_bbb.o $BBB_PATH/build/source/render.o $BBB_PATH/build/source/render.d";
+
+# Make new BeagleRT executable and run
+if [ $RUN_PROJECT -eq 0 ]
+then
+    echo "Building project..."
+    ssh $BBB_ADDRESS "make all -C $BBB_PATH"
+else
+    echo "Building and running project..."
+    
+    if [ $RUN_WITHOUT_SCREEN -ne 0 ]
+    then
+        ssh -t $BBB_ADDRESS "make all -C $BBB_PATH && $BBB_PATH/BeagleRT $COMMAND_ARGS" 
+    elif [ $RUN_IN_FOREGROUND -eq 0 ]
+    then
+        ssh $BBB_ADDRESS "make all -C $BBB_PATH && screen -S BeagleRT -d -m $BBB_PATH/BeagleRT $COMMAND_ARGS"
+    else
+        ssh -t $BBB_ADDRESS "make all -C $BBB_PATH && screen -S BeagleRT $BBB_PATH/BeagleRT $COMMAND_ARGS"
+    fi
+fi
+
+
+
+
+
+
+
+
+#ssh -t root@192.168.7.2 "kill -s 2 \`pidof heavy_template\` 2>/dev/null; sleep 0.5; rm -f ~/$filename_bbb/Release/source/heavy/HvContext_bbb.? ~/$filename_bbb/Release/heavy_template && make all -C ~/$filename_bbb/Release" &>/dev/null
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/scripts/hvresources/render.cpp	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,146 @@
+/*
+ * render.cpp
+ *
+ *  Template render.cpp file for on-board heavy compiling
+ *
+ *  N.B. this is currently *not* compatible with foleyDesigner source files!
+ *
+ *  Created on: November 5, 2015
+ *
+ *  Christian Heinrichs
+ *
+ */
+
+#include <BeagleRT.h>
+#include <cmath>
+#include "../include/Utilities.h"
+#include "Heavy_bbb.h"
+
+/*
+ *	HEAVY CONTEXT & BUFFERS
+ */
+
+Hv_bbb *gHeavyContext;
+float *gHvInputBuffers = NULL, *gHvOutputBuffers = NULL;
+int gHvInputChannels = 0, gHvOutputChannels = 0;
+
+float gInverseSampleRate;
+
+/*
+ *	HEAVY FUNCTIONS
+ */
+
+void printHook(double timestampSecs, const char *printLabel, const char *msgString, void *userData) {
+  printf("Message from Heavy patch: [@ %.3f] %s: %s\n", timestampSecs, printLabel, msgString);
+}
+
+static void sendHook(
+    double timestamp, // in milliseconds
+    const char *receiverName,
+    const HvMessage *const m,
+    void *userData) {
+
+  // only react to messages sent to receivers named "hello"
+  if (!strncmp(receiverName, "hello", 5)) {
+  }
+
+}
+
+/*
+ * SETUP, RENDER LOOP & CLEANUP
+ */
+
+bool setup(BeagleRTContext *context, void *userData)	{
+
+	/* HEAVY */
+
+	gHeavyContext = hv_bbb_new(context->audioSampleRate);
+
+	gHvInputChannels = hv_getNumInputChannels(gHeavyContext);
+	gHvOutputChannels = hv_getNumOutputChannels(gHeavyContext);
+
+	rt_printf("Starting Heavy context with %d input channels and %d output channels\n",
+			  gHvInputChannels, gHvOutputChannels);
+
+	if(gHvInputChannels != 0) {
+		gHvInputBuffers = (float *)calloc(gHvInputChannels * context->audioFrames,sizeof(float));
+	}
+	if(gHvOutputChannels != 0) {
+		gHvOutputBuffers = (float *)calloc(gHvOutputChannels * context->audioFrames,sizeof(float));
+	}
+
+	gInverseSampleRate = 1.0 / context->audioSampleRate;
+
+	// Set heavy print hook
+	hv_setPrintHook(gHeavyContext, &printHook);
+	// Set heavy send hook
+	hv_setSendHook(gHeavyContext, sendHook);
+
+	return true;
+}
+
+
+void render(BeagleRTContext *context, void *userData)
+{
+
+	// De-interleave the data
+	if(gHvInputBuffers != NULL) {
+		for(int n = 0; n < context->audioFrames; n++) {
+			for(int ch = 0; ch < gHvInputChannels; ch++) {
+				if(ch >= context->audioChannels+context->analogChannels) {
+					// THESE ARE PARAMETER INPUT 'CHANNELS' USED FOR ROUTING
+					// 'sensor' outputs from routing channels of dac~ are passed through here
+					break;
+				} else {
+					// If more than 2 ADC inputs are used in the pd patch, route the analog inputs
+					// i.e. ADC3->analogIn0 etc. (first two are always audio inputs)
+					if(ch >= context->audioChannels)	{
+						int m = n/2;
+						float mIn = context->analogIn[m*context->analogChannels + (ch-context->audioChannels)];
+						gHvInputBuffers[ch * context->audioFrames + n] = mIn;
+					} else {
+						gHvInputBuffers[ch * context->audioFrames + n] = context->audioIn[n * context->audioChannels + ch];
+					}
+				}
+			}
+		}
+	}
+
+	// replacement for bang~ object
+	//hv_vscheduleMessageForReceiver(gHeavyContext, "bbb_bang", 0.0f, "b");
+
+	hv_bbb_process_inline(gHeavyContext, gHvInputBuffers, gHvOutputBuffers, context->audioFrames);
+
+	// Interleave the output data
+	if(gHvOutputBuffers != NULL) {
+		for(int n = 0; n < context->audioFrames; n++) {
+
+			for(int ch = 0; ch < gHvOutputChannels; ch++) {
+				if(ch >= context->audioChannels+context->analogChannels) {
+					// THESE ARE SENSOR OUTPUT 'CHANNELS' USED FOR ROUTING
+					// they are the content of the 'sensor output' dac~ channels
+				} else {
+					if(ch >= context->audioChannels)	{
+						int m = n/2;
+						context->analogOut[m * context->analogFrames + (ch-context->audioChannels)] = constrain(gHvOutputBuffers[ch*context->audioFrames + n],0.0,1.0);
+					} else {
+						context->audioOut[n * context->audioChannels + ch] = gHvOutputBuffers[ch * context->audioFrames + n];
+					}
+				}
+			}
+		}
+	}
+
+}
+
+
+void cleanup(BeagleRTContext *context, void *userData)
+{
+
+	hv_bbb_free(gHeavyContext);
+	if(gHvInputBuffers != NULL)
+		free(gHvInputBuffers);
+	if(gHvOutputBuffers != NULL)
+		free(gHvOutputBuffers);
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/scripts/hvresources/uploader.py	Mon Dec 28 03:19:59 2015 +0100
@@ -0,0 +1,280 @@
+#!/usr/bin/python
+
+# Copyright 2015 Section6. All Rights Reserved.
+
+import argparse
+import getpass
+import json
+import os
+import requests
+import shutil
+import stat
+import tempfile
+import time
+import urlparse
+import zipfile
+import sys
+
+class Colours:
+    purple = "\033[95m"
+    cyan = "\033[96m"
+    dark_cyan = "\033[36m"
+    blue = "\033[94m"
+    green = "\033[92m"
+    yellow = "\033[93m"
+    red = "\033[91m"
+    bold = "\033[1m"
+    underline = "\033[4m"
+    end = "\033[0m"
+
+def __zip_dir(in_dir, zip_path, file_filter=None):
+    zf = zipfile.ZipFile(zip_path, mode="w", compression=zipfile.ZIP_DEFLATED)
+    for subdir, dirs, files in os.walk(in_dir):
+        for file in files:
+            if (file_filter is None) or (len(file_filter) > 0 and file.lower().split(".")[-1] in file_filter):
+                zf.write(
+                    filename=os.path.join(subdir,file),
+                    arcname=os.path.relpath(os.path.join(subdir,file), start=in_dir))
+    return zip_path
+
+def __unzip(zip_path, target_dir):
+    """Unzip a file to a given directory. All destination files are overwritten.
+    """
+    zipfile.ZipFile(zip_path).extractall(target_dir)
+
+def main():
+    parser = argparse.ArgumentParser(
+        description="Compiles a Pure Data file.")
+    parser.add_argument(
+        "input_dir",
+        help="A directory containing _main.pd. The entire directory will be uploaded.")
+    parser.add_argument(
+        "-n", "--name",
+        default="heavy",
+        help="Patch name. If it doesn't exist, the uploader will fail. Make sure that it exists on the Heavy website.")
+    parser.add_argument(
+        "-g", "--gen",
+        nargs="+",
+        default=["c"],
+        help="List of generator outputs. Currently supported generators are 'c' and 'js'.")
+    parser.add_argument(
+        "-b",
+        help="All files will be placed in the output directory, placed in their own subdirectory corresonding to the generator name.",
+        action="count")
+    parser.add_argument(
+        "-o", "--out",
+        nargs="+",
+        default=["./"], # by default
+        help="List of destination directories for retrieved files. Order should be the same as for --gen.")
+    parser.add_argument(
+        "-d", "--domain",
+        default="https://enzienaudio.com",
+        help="Domain. Default is https://enzienaudio.com.")
+    parser.add_argument(
+        "-x",
+        help="Don't save the returned token.",
+        action="count")
+    parser.add_argument(
+        "-z",
+        help="Force the use of a password, regardless of saved token.",
+        action="count")
+    parser.add_argument(
+        "--noverify",
+        help="Don't verify the SSL connection. Generally a bad idea.",
+        action="count")
+    parser.add_argument(
+        "-v", "--verbose",
+        help="Show debugging information.",
+        action="count")
+    args = parser.parse_args()
+
+    domain = args.domain or "https://enzienaudio.com"
+
+    post_data = {}
+
+    # token should be stored in ~/.heavy/token
+    token_path = os.path.expanduser(os.path.join("~/", ".heavy", "token"))
+    if os.path.exists(token_path) and not args.z:
+        with open(token_path, "r") as f:
+            post_data["credentials"] = {
+                "token": f.read()
+            }
+    else:
+        # otherwise, get the username and password
+        post_data["credentials"] = {
+            "username": raw_input("Enter username: "),
+            "password": getpass.getpass("Enter password: ")
+        }
+
+    tick = time.time()
+
+    # make a temporary directory
+    temp_dir = tempfile.mkdtemp(prefix="lroyal-")
+
+    # zip up the pd directory into the temporary directory
+    try:
+        if not os.path.exists(os.path.join(args.input_dir, "_main.pd")):
+            raise Exception("Root Pd directory does not contain a file named _main.pd.")
+        zip_path = __zip_dir(
+            args.input_dir,
+            os.path.join(temp_dir, "archive.zip"),
+            file_filter={"pd"})
+    except Exception as e:
+        print e
+        shutil.rmtree(temp_dir) # clean up the temporary directory
+        return
+
+    post_data["name"] = args.name
+
+    # the outputs to generate (always include c)
+    __SUPPORTED_GENERATOR_SET = {"c", "js"}
+    post_data["gen"] = list(({"c"} | set(args.gen)) & __SUPPORTED_GENERATOR_SET)
+
+    # upload the job, get the response back
+    # NOTE(mhroth): multipart-encoded file can only be sent as a flat dictionary,
+    # but we want to send a json encoded deep dictionary. So we do a bit of a hack.
+    r = requests.post(
+        urlparse.urljoin(domain, "/a/heavy"),
+        data={"json":json.dumps(post_data)},
+        files={"file": (os.path.basename(zip_path), open(zip_path, "rb"), "application/zip")},
+        verify=False if args.noverify else True)
+
+    if r.status_code != requests.codes.ok:
+        shutil.rmtree(temp_dir) # clean up the temporary directory
+        r.raise_for_status() # raise an exception
+
+    # decode the JSON API response
+    r_json = r.json()
+
+    """
+    {
+      "data": {
+        "compileTime": 0.05078411102294922,
+        "id": "mhroth/asdf/Edp2G",
+        "slug": "Edp2G",
+        "index": 3,
+        "links": {
+          "files": {
+            "linkage": [
+              {
+                "id": "mhroth/asdf/Edp2G/c",
+                "type": "file"
+              }
+            ],
+            "self": "https://enzienaudio.com/h/mhroth/asdf/Edp2G/files"
+          },
+          "project": {
+            "linkage": {
+              "id": "mhroth/asdf",
+              "type": "project"
+            },
+            "self": "https://enzienaudio.com/h/mhroth/asdf"
+          },
+          "self": "https://enzienaudio.com/h/mhroth/asdf/Edp2G",
+          "user": {
+            "linkage": {
+              "id": "mhroth",
+              "type": "user"
+            },
+            "self": "https://enzienaudio.com/h/mhroth"
+          }
+        },
+        "type": "job"
+      },
+      "included": [
+        {
+          "filename": "file.c.zip",
+          "generator": "c",
+          "id": "mhroth/asdf/Edp2G/c",
+          "links": {
+            "self": "https://enzienaudio.com/h/mhroth/asdf/Edp2G/c/file.c.zip"
+          },
+          "mime": "application/zip",
+          "type": "file"
+        }
+      ],
+      "warnings": [],
+      "meta": {
+        "token": "11AS0qPRmjTUHEMSovPEvzjodnzB1xaz"
+      }
+    }
+    """
+    reply_json = r.json()
+    if args.verbose:
+        print json.dumps(
+            reply_json,
+            sort_keys=True,
+            indent=2,
+            separators=(",", ": "))
+
+    # update the api token, if present
+    if "token" in reply_json.get("meta",{}) and not args.x:
+        if not os.path.exists(os.path.dirname(token_path)):
+            os.makedirs(os.path.dirname(token_path)) # ensure that the .heavy directory exists
+        with open(token_path, "w") as f:
+            f.write(reply_json["meta"]["token"])
+        os.chmod(token_path, stat.S_IRUSR | stat.S_IWUSR) # force rw------- permissions on the file
+
+    # print any warnings
+    for x in r_json["warnings"]:
+        print "{0}Warning:{1} {2}".format(Colours.yellow, Colours.end, x["detail"])
+
+    # check for errors
+    if len(r_json.get("errors",[])) > 0:
+        shutil.rmtree(temp_dir) # clean up the temporary directory
+        for x in r_json["errors"]:
+            print "{0}Error:{1} {2}".format(Colours.red, Colours.end, x["detail"])
+        sys.exit(1)
+        return
+
+    # retrieve all requested files
+    for i,g in enumerate(args.gen):
+        file_url = __get_file_url_for_generator(reply_json, g)
+        if file_url is not None and (len(args.out) > i or args.b):
+            r = requests.get(
+                file_url,
+                cookies={"token": reply_json["meta"]["token"]},
+                verify=False if args.noverify else True)
+            r.raise_for_status()
+
+            # write the reply to a temporary file
+            c_zip_path = os.path.join(temp_dir, "archive.{0}.zip".format(g))
+            with open(c_zip_path, "wb") as f:
+                f.write(r.content)
+
+            # unzip the files to where they belong
+            if args.b:
+                target_dir = os.path.join(os.path.abspath(os.path.expanduser(args.out[0])), g)
+            else:
+                target_dir = os.path.abspath(os.path.expanduser(args.out[i]))
+            if not os.path.exists(target_dir):
+                os.makedirs(target_dir) # ensure that the output directory exists
+            __unzip(c_zip_path, target_dir)
+
+            print "{0} files placed in {1}".format(g, target_dir)
+        else:
+            print "{0}Warning:{1} {2} files could not be retrieved.".format(
+                Colours.yellow, Colours.end,
+                g)
+
+    # delete the temporary directory
+    shutil.rmtree(temp_dir)
+
+    print "Job URL", reply_json["data"]["links"]["self"]
+    print "Total request time: {0}ms".format(int(1000.0*(time.time()-tick)))
+
+    sys.exit(0)
+
+def __get_file_url_for_generator(json_api, g):
+    """Returns the file link for a specific generator.
+    Returns None if no link could be found.
+    """
+    for i in json_api["included"]:
+        if g == i["generator"]:
+            return i["links"]["self"]
+    return None # by default, return None
+
+
+
+if __name__ == "__main__":
+    main()