diff --git a/applications/vision/src/main.cpp b/applications/vision/src/main.cpp
index ceddbaf4c5414fd5ed9f1caddf40475169f0f515..827f4e770c2948d883a24a6ad0afcb6ec21d0e3f 100644
--- a/applications/vision/src/main.cpp
+++ b/applications/vision/src/main.cpp
@@ -17,6 +17,8 @@
 
 #include <opencv2/opencv.hpp>
 #include <ftl/rgbd.hpp>
+#include <ftl/data/framepool.hpp>
+#include <ftl/data/creators.hpp>
 //#include <ftl/middlebury.hpp>
 #include <ftl/net/universe.hpp>
 #include <ftl/master.hpp>
@@ -141,19 +143,35 @@ static void run(ftl::Configurable *root) {
 		source->set("uri", uri.getBaseURI());
 	}
 	
-	ftl::stream::Sender *sender = ftl::create<ftl::stream::Sender>(root, "sender");
+	//ftl::stream::Sender *sender = ftl::create<ftl::stream::Sender>(root, "sender");
 	ftl::stream::Net *outstream = ftl::create<ftl::stream::Net>(root, "stream", net);
 	outstream->set("uri", outstream->getID());
 	outstream->begin();
-	sender->setStream(outstream);
+	//sender->setStream(outstream);
 
-	auto *grp = new ftl::rgbd::Group();
+	/*auto *grp = new ftl::rgbd::Group();
 	source->setChannel(Channel::Depth);
-	grp->addSource(source);
+	grp->addSource(source);*/
+
+	ftl::data::Pool pool(2,5);
+	auto creator = pool.creator<ftl::data::IntervalFrameCreator>(0, source);
+
+	auto h = source->onFrame([](ftl::data::Frame &f) {
+		LOG(INFO) << "Got a frame";
+		if (f.has(ftl::codecs::Channel::Colour)) {
+			cv::Mat tmp;
+			f.get<cv::cuda::GpuMat>(ftl::codecs::Channel::Colour).download(tmp);
+			cv::imshow("Image", tmp);
+			cv::waitKey(1);
+		}
+		return true;
+	});
+
+	creator.start();
 
 	int stats_count = 0;
 
-	grp->onFrameSet([sender,&stats_count](ftl::rgbd::FrameSet &fs) {
+	/*grp->onFrameSet([sender,&stats_count](ftl::rgbd::FrameSet &fs) {
 		fs.id = 0;
 		sender->post(fs);
 
@@ -176,7 +194,7 @@ static void run(ftl::Configurable *root) {
 	pipeline->append<ftl::operators::DetectAndTrack>("facedetection")->value("enabled", false);
 	pipeline->append<ftl::operators::ArUco>("aruco")->value("enabled", false);
 	pipeline->append<ftl::operators::DepthChannel>("depth");  // Ensure there is a depth channel
-	grp->addPipeline(pipeline);
+	grp->addPipeline(pipeline);*/
 	
 	net->start();
 
@@ -189,8 +207,8 @@ static void run(ftl::Configurable *root) {
 
 	ftl::pool.stop();
 
-	delete grp;
-	delete sender;
+	//delete grp;
+	//delete sender;
 	delete outstream;
 
 	//delete source;  // TODO(Nick) Add ftl::destroy
diff --git a/applications/vision/src/middlebury.cpp b/applications/vision/src/middlebury.cpp
deleted file mode 100644
index 531cd8a0e4fd08e8b7ad2f104545e209f0d72f52..0000000000000000000000000000000000000000
--- a/applications/vision/src/middlebury.cpp
+++ /dev/null
@@ -1,301 +0,0 @@
-#include <ftl/middlebury.hpp>
-#include <loguru.hpp>
-#include <ftl/rgbd.hpp>
-
-#include <string>
-#include <algorithm>
-
-#include <nlohmann/json.hpp>
-
-#include <opencv2/highgui.hpp>
-#include <opencv2/imgproc.hpp>
-
-using cv::Mat;
-using cv::Size;
-using std::string;
-using std::min;
-using std::max;
-using std::isnan;
-
-static void skip_comment(FILE *fp) {
-    // skip comment lines in the headers of pnm files
-
-    char c;
-    while ((c=getc(fp)) == '#')
-        while (getc(fp) != '\n') ;
-    ungetc(c, fp);
-}
-
-static void skip_space(FILE *fp) {
-    // skip white space in the headers or pnm files
-
-    char c;
-    do {
-        c = getc(fp);
-    } while (c == '\n' || c == ' ' || c == '\t' || c == '\r');
-    ungetc(c, fp);
-}
-
-static void read_header(FILE *fp, const char *imtype, char c1, char c2, 
-                 int *width, int *height, int *nbands, int thirdArg)
-{
-    // read the header of a pnmfile and initialize width and height
-
-    char c;
-  
-	if (getc(fp) != c1 || getc(fp) != c2)
-		LOG(FATAL) << "ReadFilePGM: wrong magic code for " << imtype << " file";
-	skip_space(fp);
-	skip_comment(fp);
-	skip_space(fp);
-	fscanf(fp, "%d", width);
-	skip_space(fp);
-	fscanf(fp, "%d", height);
-	if (thirdArg) {
-		skip_space(fp);
-		fscanf(fp, "%d", nbands);
-	}
-    // skip SINGLE newline character after reading image height (or third arg)
-	c = getc(fp);
-    if (c == '\r')      // <cr> in some files before newline
-        c = getc(fp);
-    if (c != '\n') {
-        if (c == ' ' || c == '\t' || c == '\r')
-            LOG(FATAL) << "newline expected in file after image height";
-        else
-            LOG(FATAL) << "whitespace expected in file after image height";
-  }
-}
-
-// check whether machine is little endian
-static int littleendian() {
-    int intval = 1;
-    uchar *uval = (uchar *)&intval;
-    return uval[0] == 1;
-}
-
-// 1-band PFM image, see http://netpbm.sourceforge.net/doc/pfm.html
-// 3-band not yet supported
-void ftl::middlebury::readFilePFM(Mat &img, const string &filename)
-{
-    // Open the file and read the header
-    FILE *fp = fopen(filename.c_str(), "rb");
-    if (fp == 0)
-        LOG(FATAL) << "ReadFilePFM: could not open \"" << filename << "\"";
-
-    int width, height, nBands;
-    read_header(fp, "PFM", 'P', 'f', &width, &height, &nBands, 0);
-
-    skip_space(fp);
-
-    float scalef;
-    fscanf(fp, "%f", &scalef);  // scale factor (if negative, little endian)
-
-    // skip SINGLE newline character after reading third arg
-    char c = getc(fp);
-    if (c == '\r')      // <cr> in some files before newline
-        c = getc(fp);
-    if (c != '\n') {
-        if (c == ' ' || c == '\t' || c == '\r')
-            LOG(FATAL) << "newline expected in file after scale factor";
-        else
-            LOG(FATAL) << "whitespace expected in file after scale factor";
-    }
-    
-    // Allocate the image if necessary
-    img = Mat(height, width, CV_32FC1);
-    // Set the image shape
-    //Size sh = img.size();
-
-    int littleEndianFile = (scalef < 0);
-    int littleEndianMachine = littleendian();
-    int needSwap = (littleEndianFile != littleEndianMachine);
-    //printf("endian file = %d, endian machine = %d, need swap = %d\n", 
-    //       littleEndianFile, littleEndianMachine, needSwap);
-
-    for (int y = height-1; y >= 0; y--) { // PFM stores rows top-to-bottom!!!!
-	int n = width;
-	float* ptr = &img.at<float>(y, 0, 0);
-	if ((int)fread(ptr, sizeof(float), n, fp) != n)
-	    LOG(FATAL) << "ReadFilePFM(" << filename << "): file is too short";
-	
-	if (needSwap) { // if endianness doesn't agree, swap bytes
-	    uchar* ptr = (uchar *)&img.at<uchar>(y, 0, 0);
-	    int x = 0;
-	    uchar tmp = 0;
-	    while (x < n) {
-		tmp = ptr[0]; ptr[0] = ptr[3]; ptr[3] = tmp;
-		tmp = ptr[1]; ptr[1] = ptr[2]; ptr[2] = tmp;
-		ptr += 4;
-		x++;
-	    }
-	}
-    }
-    if (fclose(fp))
-        LOG(FATAL) << "ReadFilePGM(" << filename << "): error closing file";
-}
-
-// 1-band PFM image, see http://netpbm.sourceforge.net/doc/pfm.html
-// 3-band not yet supported
-void ftl::middlebury::writeFilePFM(const Mat &img, const char* filename, float scalefactor)
-{
-    // Write a PFM file
-    Size sh = img.size();
-    int nBands = img.channels();
-    if (nBands != 1)
-	LOG(FATAL) << "WriteFilePFM(" << filename << "): can only write 1-band image as pfm for now";
-	
-    // Open the file
-    FILE *stream = fopen(filename, "wb");
-    if (stream == 0)
-        LOG(FATAL) << "WriteFilePFM: could not open " << filename;
-
-    // sign of scalefact indicates endianness, see pfms specs
-    if (littleendian())
-	scalefactor = -scalefactor;
-
-    // write the header: 3 lines: Pf, dimensions, scale factor (negative val == little endian)
-    fprintf(stream, "Pf\n%d %d\n%f\n", sh.width, sh.height, scalefactor);
-
-    int n = sh.width;
-    // write rows -- pfm stores rows in inverse order!
-    for (int y = sh.height-1; y >= 0; y--) {
-	const float* ptr = &img.at<float>(0, y, 0);
-	if ((int)fwrite(ptr, sizeof(float), n, stream) != n)
-	    LOG(FATAL) << "WriteFilePFM(" << filename << "): file is too short";
-    }
-    
-    // close file
-    if (fclose(stream))
-        LOG(FATAL) << "WriteFilePFM(" << filename << "): error closing file";
-}
-
-void ftl::middlebury::evaldisp(const Mat &disp, const Mat &gtdisp, const Mat &mask, float badthresh, int maxdisp, int rounddisp)
-{
-    Size sh = gtdisp.size();
-    Size sh2 = disp.size();
-    Size msh = mask.size();
-    int width = sh.width, height = sh.height;
-    int width2 = sh2.width, height2 = sh2.height;
-    int scale = width / width2;
-
-    if ((!(scale == 1 || scale == 2 || scale == 4))
-	|| (scale * width2 != width)
-	|| (scale * height2 != height)) {
-	printf("   disp size = %4d x %4d\n", width2, height2);
-	printf("GT disp size = %4d x %4d\n", width,  height);
-	LOG(ERROR) << "GT disp size must be exactly 1, 2, or 4 * disp size";
-    }
-
-    int usemask = (msh.width > 0 && msh.height > 0);
-    if (usemask && (msh != sh))
-	LOG(ERROR) << "mask image must have same size as GT";
-
-    int n = 0;
-    int bad = 0;
-    int invalid = 0;
-    float serr = 0;
-    for (int y = 0; y < height; y++) {
-	for (int x = 0; x < width; x++) {
-	    float gt = gtdisp.at<float>(y, x, 0);
-	    if (gt == INFINITY) // unknown
-		continue;
-	    float d = scale * disp.at<float>(y / scale, x / scale, 0);
-	    int valid = (!isnan(d) && d < 256.0f); // NOTE: Is meant to be infinity in middlebury
-	    if (valid) {
-		float maxd = scale * maxdisp; // max disp range
-		d = max(0.0f, min(maxd, d)); // clip disps to max disp range
-	    }
-	    if (valid && rounddisp)
-		d = round(d);
-	    float err = fabs(d - gt);
-	    if (usemask && mask.at<float>(y, x, 0) != 255) { // don't evaluate pixel
-	    } else {
-		n++;
-		if (valid) {
-		    serr += err;
-		    if (err > badthresh) {
-			bad++;
-		    }
-		} else {// invalid (i.e. hole in sparse disp map)
-		    invalid++;
-		}
-	    }
-	}
-    }
-    float badpercent =  100.0*bad/n;
-    float invalidpercent =  100.0*invalid/n;
-    float totalbadpercent =  100.0*(bad+invalid)/n;
-    float avgErr = serr / (n - invalid); // CHANGED 10/14/2014 -- was: serr / n
-    printf("mask  bad%.1f  invalid  totbad   avgErr\n", badthresh);
-    printf("%4.1f  %6.2f  %6.2f   %6.2f  %6.2f\n",   100.0*n/(width * height), 
-	   badpercent, invalidpercent, totalbadpercent, avgErr);
-}
-
-void ftl::middlebury::test(nlohmann::json &config) {
-	// Load dataset images
-	Mat l = cv::imread((string)config["middlebury"]["dataset"] + "/im0.png");
-	Mat r = cv::imread((string)config["middlebury"]["dataset"] + "/im1.png");
-	
-	// Load ground truth
-	Mat gt;
-	readFilePFM(gt, (string)config["middlebury"]["dataset"] + "/disp0.pfm");
-	
-	if ((float)config["middlebury"]["scale"] != 1.0f) {
-		float scale = (float)config["middlebury"]["scale"];
-		//cv::resize(gt, gt, cv::Size(gt.cols * scale,gt.rows * scale), 0, 0, cv::INTER_LINEAR);
-		cv::resize(l, l, cv::Size(l.cols * scale,l.rows * scale), 0, 0, cv::INTER_LINEAR);
-		cv::resize(r, r, cv::Size(r.cols * scale,r.rows * scale), 0, 0, cv::INTER_LINEAR);
-	}
-	
-	// TODO(Nick) Update to use an RGBD Image source
-	// Run algorithm
-	//auto disparity = ftl::Disparity::create(config["disparity"]);
-    
-    Mat disp;
-   // disparity->compute(l,r,disp);
-	//disp.convertTo(disp, CV_32F);
-	
-	// Display results
-	evaldisp(disp, gt, Mat(), (float)config["middlebury"]["threshold"], (int)config["disparity"]["maximum"], 0);
-	
-	/*if (gt.cols > 1600) {
-		cv::resize(gt, gt, cv::Size(gt.cols * 0.25,gt.rows * 0.25), 0, 0, cv::INTER_LINEAR);
-	}*/
-	if (disp.cols > 1600) {
-		cv::resize(disp, disp, cv::Size(disp.cols * 0.25,disp.rows * 0.25), 0, 0, cv::INTER_LINEAR);
-	}
-    cv::resize(gt, gt, cv::Size(disp.cols,disp.rows), 0, 0, cv::INTER_LINEAR);
-	
-	double mindisp, mindisp_gt;
-	double maxdisp, maxdisp_gt;
-	Mat mask;
-	threshold(disp,mask,255.0, 255, cv::THRESH_BINARY_INV);
-	normalize(mask, mask, 0, 255, cv::NORM_MINMAX, CV_8U);
-	cv::minMaxLoc(disp, &mindisp, &maxdisp, 0, 0, mask);
-    cv::minMaxLoc(gt, &mindisp_gt, &maxdisp_gt, 0, 0);
-
-    //disp = (disp < 256.0f);
-    //disp = disp + (mindisp_gt - mindisp);
-    disp.convertTo(disp, CV_8U, 255.0f / (maxdisp_gt*(float)config["middlebury"]["scale"]));
-    disp = disp & mask;
-
-	gt = gt / maxdisp_gt; // TODO Read from calib.txt
-    gt.convertTo(gt, CV_8U, 255.0f);
-	//disp = disp / maxdisp;
-	imshow("Ground Truth", gt);
-	imshow("Disparity", disp);
-    imshow("Diff", gt - disp);
-	
-	while (cv::waitKey(10) != 27);
-	
-	/*cv::putText(yourImageMat, 
-            "Here is some text",
-            cv::Point(5,5), // Coordinates
-            cv::FONT_HERSHEY_COMPLEX_SMALL, // Font
-            1.0, // Scale. 2.0 = 2x bigger
-            cv::Scalar(255,255,255), // BGR Color
-            1, // Line Thickness (Optional)
-            cv::CV_AA); // Anti-alias (Optional)*/
-}
-
diff --git a/applications/vision/src/streamer.cpp b/applications/vision/src/streamer.cpp
deleted file mode 100644
index 29b84568cbba3f94d54ef16a6599fbb398394085..0000000000000000000000000000000000000000
--- a/applications/vision/src/streamer.cpp
+++ /dev/null
@@ -1,64 +0,0 @@
-#include <loguru.hpp>
-#include <ftl/streamer.hpp>
-#include <vector>
-// #include <zlib.h>
-// #include <lz4.h>
-
-using ftl::Streamer;
-using ftl::net::Universe;
-using cv::Mat;
-using nlohmann::json;
-using std::string;
-using std::vector;
-
-Streamer::Streamer(Universe &net, json &config) : net_(net), config_(config) {
-	uri_ = string("ftl://utu.fi/")+(string)config["name"]+string("/rgb-d");
-	net.createResource(uri_);
-}
-
-Streamer::~Streamer() {
-
-}
-
-void Streamer::send(const Mat &rgb, const Mat &depth) {
-	// Compress the rgb as jpeg.
-	vector<unsigned char> rgb_buf;
-	cv::imencode(".jpg", rgb, rgb_buf);
-	
-	Mat d2;
-    depth.convertTo(d2, CV_16UC1, 16*100);
-	
-	vector<unsigned char> d_buf;
-	/*d_buf.resize(d2.step*d2.rows);
-	z_stream defstream;
-    defstream.zalloc = Z_NULL;
-    defstream.zfree = Z_NULL;
-    defstream.opaque = Z_NULL;
-    defstream.avail_in = d2.step*d2.rows;
-    defstream.next_in = (Bytef *)d2.data; // input char array
-    defstream.avail_out = (uInt)d2.step*d2.rows; // size of output
-    defstream.next_out = (Bytef *)d_buf.data(); // output char array
-    
-    deflateInit(&defstream, Z_DEFAULT_COMPRESSION);
-    deflate(&defstream, Z_FINISH);
-    deflateEnd(&defstream);
-    
-    d2.copyTo(last);
-    
-    d_buf.resize(defstream.total_out);*/
-    
-    // LZ4 Version
-    // d_buf.resize(LZ4_compressBound(depth.step*depth.rows));
-    // int s = LZ4_compress_default((char*)depth.data, (char*)d_buf.data(), depth.step*depth.rows, d_buf.size());
-    // d_buf.resize(s);
-
-    cv::imencode(".png", d2, d_buf);
-    //LOG(INFO) << "Depth Size = " << ((float)d_buf.size() / (1024.0f*1024.0f));
-
-	try {
-    	net_.publish(uri_, rgb_buf, d_buf);
-	} catch (...) {
-		LOG(ERROR) << "Exception on net publish to " << uri_;
-	}
-}
-
diff --git a/applications/vision/src/sync.cpp b/applications/vision/src/sync.cpp
deleted file mode 100644
index 8d1671a3fba63e10310bf5e0f6e9f69d06e8c97b..0000000000000000000000000000000000000000
--- a/applications/vision/src/sync.cpp
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#include <ftl/synched.hpp>
-
-using ftl::SyncSource;
-using cv::Mat;
-
-SyncSource::SyncSource() {
-	channels_.push_back(Mat());
-	channels_.push_back(Mat());
-}
-
-void SyncSource::addChannel(const std::string &c) {
-}
-
-void SyncSource::feed(int channel, cv::Mat &m, double ts) {
-	if (channel > static_cast<int>(channels_.size())) return;
-	channels_[channel] = m;
-}
-
-bool SyncSource::get(int channel, cv::Mat &m) {
-	if (channel > static_cast<int>(channels_.size())) return false;
-	m = channels_[channel];
-	return true;
-}
-
-double SyncSource::latency() const {
-	return 0.0;
-}
-
diff --git a/components/rgbd-sources/include/ftl/rgbd/frame.hpp b/components/rgbd-sources/include/ftl/rgbd/frame.hpp
index 9ecd6404a040fbd297abe0c49a12fb0fce50c458..5ba92cd49bbcfd1a23e847256b6890104790cb96 100644
--- a/components/rgbd-sources/include/ftl/rgbd/frame.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/frame.hpp
@@ -76,11 +76,11 @@ class VideoFrame {
 
 class Frame : public ftl::data::Frame {
 	public:
-	inline const ftl::rgbd::Camera &getLeftCamera() { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration); }
-	inline const ftl::rgbd::Camera &getRightCamera() { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration2); }
-	inline const ftl::rgbd::Camera &getLeft() { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration); }
-	inline const ftl::rgbd::Camera &getRight() { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration2); }
-	inline const Eigen::Matrix4d &getPose() { return this->get<Eigen::Matrix4d>(ftl::codecs::Channel::Pose); }
+	inline const ftl::rgbd::Camera &getLeftCamera() const { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration); }
+	inline const ftl::rgbd::Camera &getRightCamera() const { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration2); }
+	inline const ftl::rgbd::Camera &getLeft() const { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration); }
+	inline const ftl::rgbd::Camera &getRight() const { return this->get<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration2); }
+	inline const Eigen::Matrix4d &getPose() const { return this->get<Eigen::Matrix4d>(ftl::codecs::Channel::Pose); }
 	inline ftl::rgbd::Camera &setLeft() { return this->create<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration); }
 	inline ftl::rgbd::Camera &setRight() { return this->create<ftl::rgbd::Camera>(ftl::codecs::Channel::Calibration2); }
 	inline Eigen::Matrix4d &setPose() { return this->create<Eigen::Matrix4d>(ftl::codecs::Channel::Pose); }
diff --git a/components/rgbd-sources/include/ftl/rgbd/source.hpp b/components/rgbd-sources/include/ftl/rgbd/source.hpp
index 69ee9983eee544fd29df2603c0000d4a2b494967..a7eae31090446e5794fc3964b40184a1a8b98b0b 100644
--- a/components/rgbd-sources/include/ftl/rgbd/source.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/source.hpp
@@ -14,6 +14,7 @@
 
 #include <ftl/cuda_common.hpp>
 #include <ftl/data/new_frame.hpp>
+#include <ftl/data/creators.hpp>
 
 namespace ftl {
 
@@ -36,7 +37,7 @@ static inline bool isValidDepth(float d) { return (d > 0.01f) && (d < 39.99f); }
  * Cannot be constructed directly, use ftl::create<Source>(...).
  * @see ftl::create
  */
-class Source : public ftl::Configurable {
+class Source : public ftl::Configurable, public ftl::data::DiscreteSource {
 	public:
 	template <typename T, typename... ARGS>
 	friend T *ftl::config::create(ftl::config::json_t &, ARGS ...);
@@ -74,12 +75,12 @@ class Source : public ftl::Configurable {
 	 * Perform the hardware or virtual frame grab operation. This should be
 	 * fast and non-blocking. 
 	 */
-	bool capture(int64_t ts);
+	bool capture(int64_t ts) override;
 
 	/**
 	 * Download captured frame. This could be a blocking IO operation.
 	 */
-	bool retrieve(ftl::data::Frame &);
+	bool retrieve(ftl::data::Frame &) override;
 
 	/**
 	 * Generate a thread job using the provided callback for the most recently
@@ -145,14 +146,7 @@ class Source : public ftl::Configurable {
 	 * There can be only a single such callback as the buffers can be swapped
 	 * by the callback.
 	 */
-	ftl::Handle setCallback(const std::function<bool(ftl::data::Frame&)> &cb);
-
-	/**
-	 * Notify of a decoded or available pair of frames. This calls the source
-	 * callback after having verified the correct resolution of the frames.
-	 */
-	//void notify(int64_t ts, cv::cuda::GpuMat &c1, cv::cuda::GpuMat &c2);
-	//void notify(int64_t ts, ftl::rgbd::Frame &f);
+	ftl::Handle onFrame(const std::function<bool(ftl::data::Frame&)> &cb);
 
 
 	private:
diff --git a/components/rgbd-sources/src/source.cpp b/components/rgbd-sources/src/source.cpp
index a12a022657762a662196ad486aeb1319e8363f24..53da6a071ec63e9ade56ae93711b7d82ff05f0ef 100644
--- a/components/rgbd-sources/src/source.cpp
+++ b/components/rgbd-sources/src/source.cpp
@@ -187,7 +187,7 @@ bool Source::retrieve(ftl::data::Frame &f) {
 	bool status = false;
 	if (impl_) status = impl_->retrieve(f.cast<ftl::rgbd::Frame>());
 	is_retrieving = false;
-	return status;
+	return status && dispatch(f);
 }
 
 bool Source::dispatch(ftl::data::Frame &f) {
@@ -200,9 +200,10 @@ bool Source::dispatch(ftl::data::Frame &f) {
 
 	// FIXME: must still have a swap to keep f
 
+
 	//_swap();
-	ftl::pool.push([this,&f](int id) {
-		callback_.trigger(f.cast<ftl::rgbd::Frame>());
+	ftl::pool.push([this, ff = std::move(f)] (int id) mutable {
+		callback_.trigger(ff.cast<ftl::rgbd::Frame>());
 		is_dispatching = false;
 	});
 	return true;
@@ -224,7 +225,7 @@ const ftl::rgbd::Camera Source::parameters(ftl::codecs::Channel chan) const {
 	return (impl_) ? impl_->parameters(chan) : parameters();
 }
 
-ftl::Handle Source::setCallback(const std::function<bool(ftl::data::Frame&)> &cb) {
+ftl::Handle Source::onFrame(const std::function<bool(ftl::data::Frame&)> &cb) {
 	return callback_.on(cb);
 }
 
diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp
index cd74e0d62cd64e11217abd934ea3512416d5a946..1fcd531101db4c4f4f525cbdf456c233ec07ecdd 100644
--- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp
+++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp
@@ -248,7 +248,7 @@ void StereoVideoSource::updateParameters(ftl::rgbd::Frame &frame) {
 
 	frame.setPose() = pose;
 
-	frame.set<std::string>(Channel::Name) = host_->value("name", host_->getID());
+	frame.create<std::string>(Channel::Name) = host_->value("name", host_->getID());
 
 	cv::Mat K;
 
diff --git a/components/streams/CMakeLists.txt b/components/streams/CMakeLists.txt
index 43722b88881e64e3517a63b225811437bcce7f05..006e01465b9f8d19941feaee3eb23ddccbd52cce 100644
--- a/components/streams/CMakeLists.txt
+++ b/components/streams/CMakeLists.txt
@@ -8,8 +8,8 @@
 set(STREAMSRC
 	src/stream.cpp
 	src/filestream.cpp
-	src/receiver.cpp
-	src/sender.cpp
+	#src/receiver.cpp
+	#src/sender.cpp
 	src/netstream.cpp
 	src/injectors.cpp
 	src/parsers.cpp
diff --git a/components/streams/include/ftl/streams/feed.hpp b/components/streams/include/ftl/streams/feed.hpp
index b2f3f49307d2bc32eeed56647d6a791c43f6b059..80f028393fd8a9c32de8bb5cfaa338b8ae90f0c7 100644
--- a/components/streams/include/ftl/streams/feed.hpp
+++ b/components/streams/include/ftl/streams/feed.hpp
@@ -13,7 +13,9 @@ using FrameSetHandler = std::function<bool(ftl::data::FrameSet&)>;
 class Feed : public ftl::Configurable {
 	public:
 
-	void addStream(ftl::streams::Stream *s);
+	void add(ftl::streams::Stream *s);
+	void add(ftl::rgbd::Source *s);
+	void add(const std::string &uri);
 
 	ftl::Handle onFrameSet(const FrameSetHandler &fsh);
 
diff --git a/components/streams/include/ftl/streams/injectors.hpp b/components/streams/include/ftl/streams/injectors.hpp
index 0d2a35aeee928d89362c133f641b7b8f118061a8..b1bd707457ebd8613d20d6916337dff0b4a91341 100644
--- a/components/streams/include/ftl/streams/injectors.hpp
+++ b/components/streams/include/ftl/streams/injectors.hpp
@@ -2,6 +2,7 @@
 #define _FTL_STREAM_INJECTORS_HPP_
 
 #include <ftl/streams/stream.hpp>
+#include <ftl/rgbd/frameset.hpp>
 
 namespace ftl {
 namespace stream {
diff --git a/components/streams/include/ftl/streams/receiver.hpp b/components/streams/include/ftl/streams/receiver.hpp
index 23eb55a0d02c325fe4092b110532f67863a1a506..838c5995085d167fbc91c9b2505117106f2162e4 100644
--- a/components/streams/include/ftl/streams/receiver.hpp
+++ b/components/streams/include/ftl/streams/receiver.hpp
@@ -34,7 +34,7 @@ class Receiver : public ftl::Configurable {
 	 * Register a callback for received framesets. Sources are automatically
 	 * created to match the data received.
 	 */
-	ftl::Handle onFrameSet(const ftl::data::FrameSet &cb);
+	ftl::Handle onFrameSet(const std::function<bool(ftl::data::FrameSet &)> &cb);
 
 	/**
 	 * Add a frameset handler to a specific stream ID.
diff --git a/components/streams/src/injectors.cpp b/components/streams/src/injectors.cpp
index 539c9d3765d36a9970137265b4ebc96dab359a6b..bc7644b98dfba52a0d8ce020daf4faf4f27ff563 100644
--- a/components/streams/src/injectors.cpp
+++ b/components/streams/src/injectors.cpp
@@ -5,17 +5,17 @@ using ftl::codecs::Channel;
 using ftl::util::FTLVectorBuffer;
 
 void ftl::stream::injectCalibration(ftl::stream::Stream *stream, const ftl::rgbd::FrameSet &fs, int ix, bool right) {
-	ftl::stream::injectCalibration(stream, fs.frames[ix], fs.timestamp, fs.id, ix, right);
+	ftl::stream::injectCalibration(stream, fs.frames[ix].cast<ftl::rgbd::Frame>(), fs.timestamp(), fs.frameset(), ix, right);
 }
 
 void ftl::stream::injectPose(ftl::stream::Stream *stream, const ftl::rgbd::FrameSet &fs, int ix) {
-	ftl::stream::injectPose(stream, fs.frames[ix], fs.timestamp, ix);
+	ftl::stream::injectPose(stream, fs.frames[ix].cast<ftl::rgbd::Frame>(), fs.timestamp(), ix);
 }
 
 void ftl::stream::injectConfig(ftl::stream::Stream *stream, const ftl::rgbd::FrameSet &fs, int ix) {
 	ftl::codecs::StreamPacket spkt = {
 		4,
-		fs.timestamp,
+		fs.timestamp(),
 		0,
 		static_cast<uint8_t>(ix),
 		Channel::Configuration
@@ -29,7 +29,7 @@ void ftl::stream::injectConfig(ftl::stream::Stream *stream, const ftl::rgbd::Fra
 	pkt.flags = 0;
 
 	FTLVectorBuffer buf(pkt.data);
-	msgpack::pack(buf, fs.frames[ix].getConfigString());
+	//msgpack::pack(buf, fs.frames[ix].getConfigString());
 
 	stream->post(spkt, pkt);
 }
diff --git a/components/streams/src/sender.cpp b/components/streams/src/sender.cpp
index 37f23525c50458bc2ea524a9e80d033379896d5c..d3f6dd502c807b493bc1675e19b5227c3a20d6d3 100644
--- a/components/streams/src/sender.cpp
+++ b/components/streams/src/sender.cpp
@@ -87,31 +87,33 @@ void Sender::post(const ftl::audio::FrameSet &fs) {
 			fs.frames[i].get<ftl::audio::Audio>(Channel::AudioStereo) :
 			fs.frames[i].get<ftl::audio::Audio>(Channel::AudioMono);
 
-		auto &settings = fs.frames[i].getSettings();
+		//auto &settings = fs.frames[i].getSettings();
 
 		StreamPacket spkt;
 		spkt.version = 4;
-		spkt.timestamp = fs.timestamp;
-		spkt.streamID = fs.id;
+		spkt.timestamp = fs.timestamp();
+		spkt.streamID = fs.frameset();
 		spkt.frame_number = i;
 		spkt.channel = (fs.frames[i].hasChannel(Channel::AudioStereo)) ? Channel::AudioStereo : Channel::AudioMono;
 
 		ftl::codecs::Packet pkt;
 		pkt.codec = ftl::codecs::codec_t::OPUS;
-		pkt.definition = ftl::codecs::definition_t::Any;
+		//pkt.definition = ftl::codecs::definition_t::Any;
 
-		switch (settings.sample_rate) {
+		/*switch (settings.sample_rate) {
 		case 48000		: pkt.definition = ftl::codecs::definition_t::hz48000; break;
 		case 44100		: pkt.definition = ftl::codecs::definition_t::hz44100; break;
 		default: break;
-		}
+		}*/
+
+		pkt.definition = ftl::codecs::definition_t::hz48000;
 
 		pkt.frame_count = 1;
 		pkt.flags = (fs.frames[i].hasChannel(Channel::AudioStereo)) ? ftl::codecs::kFlagStereo : 0;
 		pkt.bitrate = 180;
 
 		// Find encoder here ...
-		ftl::audio::Encoder *enc = _getAudioEncoder(fs.id, i, spkt.channel, pkt);
+		ftl::audio::Encoder *enc = _getAudioEncoder(fs.id(), i, spkt.channel, pkt);
 
 		// Do encoding into pkt.data
 		if (!enc) {
@@ -175,7 +177,7 @@ void Sender::post(ftl::rgbd::FrameSet &fs) {
 	FTL_Profile("SenderPost", 0.02);
 
 	// Send any frameset data channels
-	for (auto c : fs.getDataChannels()) {
+	/*for (auto c : fs.getDataChannels()) {
 		StreamPacket spkt;
 		spkt.version = 4;
 		spkt.timestamp = fs.timestamp;
@@ -190,7 +192,7 @@ void Sender::post(ftl::rgbd::FrameSet &fs) {
 		pkt.bitrate = 0;
 		pkt.data = fs.getRawData(c);
 		stream_->post(spkt, pkt);
-	}
+	}*/
 
 	for (size_t i=0; i<fs.frames.size(); ++i) {
 		const auto &frame = fs.frames[i];
@@ -202,14 +204,14 @@ void Sender::post(ftl::rgbd::FrameSet &fs) {
 			injectPose(stream_, fs, i);
 			injectConfig(stream_, fs, i);
 		} else {
-			if (frame.hasChanged(Channel::Pose)) injectPose(stream_, fs, i);
-			if (frame.hasChanged(Channel::Calibration)) injectCalibration(stream_, fs, i);
-			if (frame.hasChanged(Channel::Calibration2)) injectCalibration(stream_, fs, i, true);
-			if (frame.hasChanged(Channel::Configuration)) injectConfig(stream_, fs, i);
+			if (frame.changed(Channel::Pose)) injectPose(stream_, fs, i);
+			if (frame.changed(Channel::Calibration)) injectCalibration(stream_, fs, i);
+			if (frame.changed(Channel::Calibration2)) injectCalibration(stream_, fs, i, true);
+			if (frame.changed(Channel::Configuration)) injectConfig(stream_, fs, i);
 		}
 
 		// FIXME: Allow data channel selection rather than always send
-		for (auto c : frame.getDataChannels()) {
+		/*for (auto c : frame.getDataChannels()) {
 			StreamPacket spkt;
 			spkt.version = 4;
 			spkt.timestamp = fs.timestamp;
@@ -224,9 +226,10 @@ void Sender::post(ftl::rgbd::FrameSet &fs) {
 			pkt.bitrate = 0;
 			pkt.data = frame.getRawData(c);
 			stream_->post(spkt, pkt);
-		}
+		}*/
 
-		for (auto c : frame.getChannels()) {
+		for (auto ic : frame.changed()) {
+			auto c = ic.first;
 			if (selected.has(c)) {
 				// FIXME: Sends high res colour, but receive end currently broken
 				//auto cc = (c == Channel::Colour && frame.hasChannel(Channel::ColourHighRes)) ? Channel::ColourHighRes : c;
@@ -234,19 +237,19 @@ void Sender::post(ftl::rgbd::FrameSet &fs) {
 
 				StreamPacket spkt;
 				spkt.version = 4;
-				spkt.timestamp = fs.timestamp;
+				spkt.timestamp = fs.timestamp();
 				spkt.streamID = 0; //fs.id;
 				spkt.frame_number = i;
 				spkt.channel = c;
 
 				// Check if there are existing encoded packets
-				const auto &packets = frame.getPackets(cc);
+				const auto &packets = frame.getEncoded(cc);
 				if (packets.size() > 0) {
 					if (packets.size() > 1) {
 						LOG(WARNING) << "Multi-packet send: " << (int)cc;
 						ftl::codecs::Packet pkt;
-						mergeNALUnits(packets, pkt);
-						stream_->post(spkt, pkt);
+						//mergeNALUnits(packets, pkt);
+						//stream_->post(spkt, pkt);
 					} else {
 						// Send existing encoding instead of re-encoding
 						//for (auto &pkt : packets) {
@@ -267,7 +270,7 @@ void Sender::post(ftl::rgbd::FrameSet &fs) {
 		// Not selected so send an empty packet...
 		StreamPacket spkt;
 		spkt.version = 4;
-		spkt.timestamp = fs.timestamp;
+		spkt.timestamp = fs.timestamp();
 		spkt.streamID = 0; // FIXME: fs.id;
 		spkt.frame_number = 255;
 		spkt.channel = c;
@@ -311,12 +314,12 @@ void Sender::_encodeChannel(ftl::rgbd::FrameSet &fs, Channel c, bool reset) {
 
 		StreamPacket spkt;
 		spkt.version = 4;
-		spkt.timestamp = fs.timestamp;
+		spkt.timestamp = fs.timestamp();
 		spkt.streamID = 0; // FIXME: fs.id;
 		spkt.frame_number = offset;
 		spkt.channel = c;
 
-		auto &tile = _getTile(fs.id, cc);
+		auto &tile = _getTile(fs.id(), cc);
 
 		ftl::codecs::Encoder *enc = tile.encoder[(offset==0)?0:1];
 		if (!enc) {
@@ -332,10 +335,12 @@ void Sender::_encodeChannel(ftl::rgbd::FrameSet &fs, Channel c, bool reset) {
 
 		// Upload if in host memory
 		for (auto &f : fs.frames) {
-			if (!fs.hasFrame(f.id)) continue;
-			if (f.isCPU(c)) {
-				f.upload(Channels<0>(cc), cv::cuda::StreamAccessor::getStream(enc->stream()));
-			}
+			if (!fs.hasFrame(f.source())) continue;
+
+			// FIXME:
+			//if (f.isCPU(c)) {
+			//	f.upload(Channels<0>(cc), cv::cuda::StreamAccessor::getStream(enc->stream()));
+			//}
 		}
 
 		int count = _generateTiles(fs, offset, cc, enc->stream(), lossless, is_stereo);
@@ -388,7 +393,7 @@ void Sender::_encodeChannel(ftl::rgbd::FrameSet &fs, Channel c, bool reset) {
 }
 
 cv::Rect Sender::_generateROI(const ftl::rgbd::FrameSet &fs, ftl::codecs::Channel c, int offset, bool stereo) {
-	const ftl::rgbd::Frame &cframe = fs.firstFrame();
+	const ftl::data::Frame &cframe = fs.firstFrame();
 	int rwidth = cframe.get<cv::cuda::GpuMat>(c).cols;
 	if (stereo) rwidth *= 2;
 	int rheight = cframe.get<cv::cuda::GpuMat>(c).rows;
@@ -425,9 +430,9 @@ float Sender::_selectFloatMax(Channel c) {
 }
 
 int Sender::_generateTiles(const ftl::rgbd::FrameSet &fs, int offset, Channel c, cv::cuda::Stream &stream, bool lossless, bool stereo) {
-	auto &surface = _getTile(fs.id, c);
+	auto &surface = _getTile(fs.id(), c);
 
-	const ftl::rgbd::Frame *cframe = nullptr; //&fs.frames[offset];
+	const ftl::data::Frame *cframe = nullptr; //&fs.frames[offset];
 
 	const auto &m = fs.firstFrame().get<cv::cuda::GpuMat>(c);
 
diff --git a/components/streams/test/CMakeLists.txt b/components/streams/test/CMakeLists.txt
index 528f439521d9866d05490e5d8bab6a2f820d8a6f..678651d9fb8b17f13eccb44bf3a66cd15a7889b2 100644
--- a/components/streams/test/CMakeLists.txt
+++ b/components/streams/test/CMakeLists.txt
@@ -36,34 +36,34 @@ add_test(FileStreamUnitTest filestream_unit)
 #add_test(NetStreamUnitTest netstream_unit)
 
 ### Sender Unit ################################################################
-add_executable(sender_unit
-$<TARGET_OBJECTS:CatchTest>
-	./sender_unit.cpp
-	../src/sender.cpp
-	../src/stream.cpp
-	../src/injectors.cpp
-	../src/parsers.cpp
-)
-target_include_directories(sender_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
-target_link_libraries(sender_unit
-	ftlcommon ftlcodecs ftlrgbd ftlaudio)
+#add_executable(sender_unit
+#$<TARGET_OBJECTS:CatchTest>
+#	./sender_unit.cpp
+#	../src/sender.cpp
+#	../src/stream.cpp
+#	../src/injectors.cpp
+#	../src/parsers.cpp
+#)
+#target_include_directories(sender_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
+#target_link_libraries(sender_unit
+#	ftlcommon ftlcodecs ftlrgbd ftlaudio)
 
-add_test(SenderUnitTest sender_unit)
+#add_test(SenderUnitTest sender_unit)
 
 ### Receiver Unit ##############################################################
-add_executable(receiver_unit
-$<TARGET_OBJECTS:CatchTest>
-	./receiver_unit.cpp
-	../src/receiver.cpp
-	../src/stream.cpp
-	../src/injectors.cpp
-	../src/parsers.cpp
-)
-target_include_directories(receiver_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
-target_link_libraries(receiver_unit
-	ftlcommon ftlcodecs ftlrgbd ftlaudio)
+#add_executable(receiver_unit
+#$<TARGET_OBJECTS:CatchTest>
+#	./receiver_unit.cpp
+#	../src/receiver.cpp
+#	../src/stream.cpp
+#	../src/injectors.cpp
+#	../src/parsers.cpp
+#)
+#target_include_directories(receiver_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
+#target_link_libraries(receiver_unit
+#	ftlcommon ftlcodecs ftlrgbd ftlaudio)
 
-add_test(ReceiverUnitTest receiver_unit)
+#add_test(ReceiverUnitTest receiver_unit)
 
 ### Builder Unit ###############################################################
 add_executable(builder_unit
diff --git a/components/structures/CMakeLists.txt b/components/structures/CMakeLists.txt
index 6d82b5854e2aa2f34ef21b347fe3038d741ac1b5..4b1a631d1c1d383a1ace922825a7ea3d33026a24 100644
--- a/components/structures/CMakeLists.txt
+++ b/components/structures/CMakeLists.txt
@@ -1,5 +1,5 @@
 
-add_library(ftldata ./src/new_frame.cpp ./src/pool.cpp ./src/frameset.cpp)
+add_library(ftldata ./src/new_frame.cpp ./src/pool.cpp ./src/frameset.cpp ./src/creators.cpp)
 
 target_include_directories(ftldata PUBLIC
 	${CMAKE_CURRENT_SOURCE_DIR}/include)
diff --git a/components/structures/include/ftl/data/creators.hpp b/components/structures/include/ftl/data/creators.hpp
index a68169e137877f6296ceea6cd04eee8c67f34846..17f7e77a9a3b674d8b5bea024d0fd0f3ccff901c 100644
--- a/components/structures/include/ftl/data/creators.hpp
+++ b/components/structures/include/ftl/data/creators.hpp
@@ -1,6 +1,9 @@
 #ifndef _FTL_DATA_FRAMECREATOR_HPP_
 #define _FTL_DATA_FRAMECREATOR_HPP_
 
+#include <ftl/handle.hpp>
+#include <ftl/data/new_frame.hpp>
+
 namespace ftl {
 namespace data {
 
@@ -19,29 +22,43 @@ class FrameCreator {
 	inline uint32_t id() const { return id_; }
 	inline Pool *pool() const { return pool_; }
 
-	private:
+	protected:
 	FrameCreator(Pool *p_pool, uint32_t p_id) : pool_(p_pool), id_(p_id) {}
 
+	private:
 	Pool *pool_;
 	uint32_t id_;
 };
 
 /**
- * Create frames at the global frame rate with both capture and retrieve steps.
+ * Abstract class for discrete data sources involving a high precision capture
+ * and slower retrieve step. This works for both cameras and audio sources.
  */
-class IntervalFrameCreator : public FrameCreator {
+class DiscreteSource {
 	public:
-	ftl::Handle onCapture(const std::function<bool(int64_t)> &cb);
-	ftl::Handle onRetrieve(const std::function<bool(Frame&)> &cb);
+	virtual bool capture(int64_t ts)=0;
+	virtual bool retrieve(ftl::data::Frame &)=0;
 };
 
 /**
- * Create a response frame rather than a primary frame.
+ * Create frames at the global frame rate with both capture and retrieve steps.
+ * A source should implement this
  */
-class ResponseFrameCreator : public FrameCreator {
+class IntervalFrameCreator : public ftl::data::FrameCreator {
+	friend class Pool;
+
+	private:
+	explicit IntervalFrameCreator(Pool *p_pool, uint32_t p_id, DiscreteSource *src);
+
 	public:
-	Frame create();
-	Frame create(int64_t timestamp);
+
+	void start();
+	void stop();
+
+	private:
+	ftl::Handle capture_;
+	ftl::Handle retrieve_;
+	DiscreteSource *src_;
 };
 
 }
diff --git a/components/structures/include/ftl/data/framepool.hpp b/components/structures/include/ftl/data/framepool.hpp
index fb08c9dd455671dbbaf6bcb9fcd5e7f2f6625587..1ea431ce856504d6f962c64f496bb4d4a1c67fcd 100644
--- a/components/structures/include/ftl/data/framepool.hpp
+++ b/components/structures/include/ftl/data/framepool.hpp
@@ -3,6 +3,7 @@
 
 #include <ftl/data/new_frame.hpp>
 #include <ftl/data/new_frameset.hpp>
+#include <ftl/data/creators.hpp>
 #include <list>
 #include <unordered_map>
 
@@ -23,6 +24,12 @@ class Pool {
 
 	size_t size();
 
+	template <typename T, typename ...ARGS>
+	T creator(uint32_t id, ARGS ...args) {
+		static_assert(std::is_base_of<ftl::data::FrameCreator, T>::value, "A creator must inherit FrameCreator");
+		return T(this, id, args...);
+	}
+
 	private:
 	struct PoolData {
 		std::list<ftl::data::Frame*> pool;
diff --git a/components/structures/include/ftl/data/new_frame.hpp b/components/structures/include/ftl/data/new_frame.hpp
index d4d33849807ebba3dd0804d1fceb8017ebc5d9d3..61da82ed7a7c2cfe36a5b72e9f531362926bce1c 100644
--- a/components/structures/include/ftl/data/new_frame.hpp
+++ b/components/structures/include/ftl/data/new_frame.hpp
@@ -8,6 +8,7 @@
 #include <list>
 #include <unordered_map>
 #include <ftl/codecs/channels.hpp>
+#include <ftl/codecs/packet.hpp>
 #include <ftl/data/channels.hpp>
 #include <ftl/exception.hpp>
 #include <ftl/handle.hpp>
@@ -166,9 +167,9 @@ class Frame {
 	ftl::data::Aggregator<T> createChange(ftl::codecs::Channel c, ftl::data::ChangeType t);
 
 	template <typename T>
-	T &createChange(ftl::codecs::Channel c, ftl::data::ChangeType t, std::vector<uint8_t> &data);
+	T &createChange(ftl::codecs::Channel c, ftl::data::ChangeType t, ftl::codecs::Packet &data);
 
-	const std::vector<uint8_t> &getEncoded(ftl::codecs::Channel c) const;
+	const std::list<ftl::codecs::Packet> &getEncoded(ftl::codecs::Channel c) const;
 
 	template <typename T, typename ...ARGS>
 	T &emplace(ftl::codecs::Channel, ARGS...);
@@ -256,6 +257,9 @@ class Frame {
 	template <typename T>
 	T &cast();
 
+	template <typename T>
+	const T &cast() const;
+
 	/**
 	 * Used to create isolated frame objects for buffer purposes. This is
 	 * deliberately separate from default constructor to force its explicit use.
@@ -265,7 +269,7 @@ class Frame {
 	protected:
 	std::any &createAnyChange(ftl::codecs::Channel c, ftl::data::ChangeType t);
 
-	std::any &createAnyChange(ftl::codecs::Channel c, ftl::data::ChangeType t, std::vector<uint8_t> &data);
+	std::any &createAnyChange(ftl::codecs::Channel c, ftl::data::ChangeType t, ftl::codecs::Packet &data);
 
 	std::any &createAny(ftl::codecs::Channel c);
 
@@ -273,7 +277,7 @@ class Frame {
 	struct ChannelData {
 		ChannelStatus status=ChannelStatus::INVALID;
 		std::any data;
-		std::vector<uint8_t> encoded={};
+		std::list<ftl::codecs::Packet> encoded={};
 	};
 
 	ChannelData &_getData(ftl::codecs::Channel);
@@ -341,6 +345,13 @@ T &ftl::data::Frame::cast() {
 	return *reinterpret_cast<T*>(this);
 }
 
+template <typename T>
+const T &ftl::data::Frame::cast() const {
+	static_assert(std::is_base_of<Frame, T>::value, "Can only cast to type inheriting Frame");
+	static_assert(sizeof(T) == sizeof(Frame), "Casting type must not have additional data members");
+	return *reinterpret_cast<const T*>(this);
+}
+
 bool ftl::data::Frame::hasOwn(ftl::codecs::Channel c) const {
 	const auto &i = data_.find(c);
 	return (i != data_.end() && i->second.status != ftl::data::ChannelStatus::INVALID);
@@ -427,7 +438,7 @@ ftl::data::Aggregator<T> ftl::data::Frame::create(ftl::codecs::Channel c) {
 }
 
 template <typename T>
-T &ftl::data::Frame::createChange(ftl::codecs::Channel c, ftl::data::ChangeType type, std::vector<uint8_t> &data) {
+T &ftl::data::Frame::createChange(ftl::codecs::Channel c, ftl::data::ChangeType type,ftl::codecs::Packet &data) {
 	if (!bool(is_list<T>{}) && isAggregate(c)) throw FTL_Error("Aggregate channels must be of list type");
 
 	ftl::data::verifyChannelType<T>(c);
diff --git a/components/structures/src/creators.cpp b/components/structures/src/creators.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..5bcd4f518e433e2213ce826d0b73dfebcfe45d0a
--- /dev/null
+++ b/components/structures/src/creators.cpp
@@ -0,0 +1,42 @@
+#include <ftl/data/creators.hpp>
+#include <ftl/data/framepool.hpp>
+#include <ftl/timer.hpp>
+
+#include <loguru.hpp>
+
+using ftl::data::Frame;
+using ftl::data::Pool;
+using ftl::data::FrameCreator;
+using ftl::data::IntervalFrameCreator;
+
+Frame FrameCreator::create() {
+	Frame f = pool_->allocate(id_, ftl::timer::get_time());
+	return f;
+}
+
+Frame FrameCreator::create(int64_t timestamp) {
+	Frame f = pool_->allocate(id_, timestamp);
+	return f;
+}
+
+IntervalFrameCreator::IntervalFrameCreator(Pool *p_pool, uint32_t p_id, DiscreteSource *src)
+	: FrameCreator(p_pool, p_id), src_(src) {}
+
+void IntervalFrameCreator::start() {
+	capture_ = std::move(ftl::timer::add(ftl::timer::timerlevel_t::kTimerHighPrecision, [this](int64_t ts) {
+		src_->capture(ts);
+		return true;
+	}));
+
+	retrieve_ = std::move(ftl::timer::add(ftl::timer::timerlevel_t::kTimerMain, [this](int64_t ts) {
+		Frame f = create(ts);
+		f.store();
+		src_->retrieve(f);
+		return true;
+	}));
+}
+
+void IntervalFrameCreator::stop() {
+	capture_.cancel();
+	retrieve_.cancel();
+}
diff --git a/components/structures/src/new_frame.cpp b/components/structures/src/new_frame.cpp
index dc2823c79239d2b25a0254238740ca906c3f2b96..5d5a934764ef0beee7287e990b35f1c207ebe55e 100644
--- a/components/structures/src/new_frame.cpp
+++ b/components/structures/src/new_frame.cpp
@@ -99,13 +99,13 @@ std::any &Frame::createAnyChange(ftl::codecs::Channel c, ftl::data::ChangeType t
 	}
 }
 
-std::any &Frame::createAnyChange(ftl::codecs::Channel c, ftl::data::ChangeType t, std::vector<uint8_t> &data) {
+std::any &Frame::createAnyChange(ftl::codecs::Channel c, ftl::data::ChangeType t, ftl::codecs::Packet &data) {
 	if (status_ != FrameStatus::CREATED) throw FTL_Error("Cannot apply change after store " << static_cast<int>(status_));
 
 	auto &d = data_[c];
 	if (d.status != ftl::data::ChannelStatus::FLUSHED) {
 		d.status = ftl::data::ChannelStatus::DISPATCHED;
-		d.encoded = std::move(data);
+		d.encoded.push_back(data);
 		touch(c, t);
 		return d.data;
 	} else {
@@ -132,7 +132,7 @@ std::any &Frame::getAnyMutable(ftl::codecs::Channel c) {
 	return d.data;
 }
 
-const std::vector<uint8_t> &ftl::data::Frame::getEncoded(ftl::codecs::Channel c) const {
+const std::list<ftl::codecs::Packet> &ftl::data::Frame::getEncoded(ftl::codecs::Channel c) const {
 	const auto &d = _getData(c);
 	if (d.status != ftl::data::ChannelStatus::INVALID) {
 		return d.encoded;
diff --git a/components/structures/test/frame_unit.cpp b/components/structures/test/frame_unit.cpp
index 8108a83d3809b7ac2b3f42d8a83626e2e548e767..d893a2d072770005dfb2a7337247572569e677d7 100644
--- a/components/structures/test/frame_unit.cpp
+++ b/components/structures/test/frame_unit.cpp
@@ -63,25 +63,27 @@ static_assert(std::is_member_function_pointer<decltype(&ftl::data::Frame::mutex)
 TEST_CASE("ftl::data::Frame encoded data", "[1.1.4]") {
 	SECTION("provide encoded data") {
 		Frame f = Feed::make(nullptr, 0, 0);
-		std::vector<uint8_t> data{44,22,33};
+		ftl::codecs::Packet data;
+		data.flags = 45;
 
 		f.createChange<int>(Channel::Pose, ftl::data::ChangeType::FOREIGN, data) = 55;
 		const auto &x = f.get<int>(Channel::Pose);
 		REQUIRE( x == 55 );
 
 		// Data has been moved.
-		REQUIRE(data.size() == 0);
+		//REQUIRE(data.size() == 0);
 	}
 
 	SECTION("get encoded data") {
 		Frame f = Feed::make(nullptr, 0, 0);
-		std::vector<uint8_t> data{44,22,33};
+		ftl::codecs::Packet data;
+		data.flags = 45;
 
 		f.createChange<int>(Channel::Pose, ftl::data::ChangeType::FOREIGN, data);
 
 		auto &data2 = f.getEncoded(Channel::Pose);
-		REQUIRE( data2.size() == 3 );
-		REQUIRE( data2[0] == 44 );
+		REQUIRE( data2.size() == 1 );
+		REQUIRE( data2.front().flags == 45 );
 	}
 }
 
@@ -89,13 +91,14 @@ TEST_CASE("ftl::data::Frame encoded data", "[1.1.4]") {
 TEST_CASE("ftl::data::Frame clear encoded on change", "[1.1.5]") {
 	SECTION("change by set") {
 		Frame f = Feed::make(nullptr, 0, 0);
-		std::vector<uint8_t> data{44,22,33};
+		ftl::codecs::Packet data;
+		data.flags = 45;
 
 		f.createChange<int>(Channel::Pose, ftl::data::ChangeType::FOREIGN, data);
 		f.store();
 
 		auto &data2 = f.getEncoded(Channel::Pose);
-		REQUIRE( data2.size() == 3 );
+		REQUIRE( data2.size() == 1 );
 		
 		f.set<int>(Channel::Pose) = 66;
 		REQUIRE(f.getEncoded(Channel::Pose).size() == 0);
@@ -103,13 +106,14 @@ TEST_CASE("ftl::data::Frame clear encoded on change", "[1.1.5]") {
 
 	SECTION("change by create") {
 		Frame f = Feed::make(nullptr, 0, 0);
-		std::vector<uint8_t> data{44,22,33};
+		ftl::codecs::Packet data;
+		data.flags = 45;
 
 		f.createChange<int>(Channel::Pose, ftl::data::ChangeType::FOREIGN, data);
 		f.store();
 
 		auto &data2 = f.getEncoded(Channel::Pose);
-		REQUIRE( data2.size() == 3 );
+		REQUIRE( data2.size() == 1 );
 		
 		f.create<int>(Channel::Pose) = 66;
 		REQUIRE(f.getEncoded(Channel::Pose).size() == 0);
@@ -664,11 +668,12 @@ TEST_CASE("ftl::data::Frame merge moves encoded", "[2.1.10]") {
 		Frame f1 = Feed::make(nullptr, 0, 0);
 		Frame f2 = Feed::make(nullptr, 0, 0);
 
-		std::vector<uint8_t> data{88,99,100};
+		ftl::codecs::Packet data;
+		data.flags = 45;
 		f1.createChange<int>(Channel::Colour, ChangeType::FOREIGN, data);
 		f2.merge(f1);
 
-		REQUIRE( f2.getEncoded(Channel::Colour).size() == 3 );
+		REQUIRE( f2.getEncoded(Channel::Colour).size() == 1 );
 		REQUIRE( !f1.has(Channel::Colour) );
 	}
 }