diff --git a/applications/gui/src/camera.cpp b/applications/gui/src/camera.cpp
index 8530915bfa14181d682fb1cad42f5e939d29184d..f35b4e539e8216b32106762b69ea7e2b028706eb 100644
--- a/applications/gui/src/camera.cpp
+++ b/applications/gui/src/camera.cpp
@@ -246,11 +246,29 @@ bool ftl::gui::Camera::setVR(bool on) {
 
 	if (on) {
 		setChannel(Channel::Right);
+		src_->set("baseline", baseline_);
+
+		Eigen::Matrix3d intrinsic;
+		
+		intrinsic = getCameraMatrix(screen_->getVR(), vr::Eye_Left);
+		CHECK(intrinsic(0, 2) < 0 && intrinsic(1, 2) < 0);
+		src_->set("focal", intrinsic(0, 0));
+		src_->set("centre_x", intrinsic(0, 2));
+		src_->set("centre_y", intrinsic(1, 2));
+		LOG(INFO) << intrinsic;
+		
+		intrinsic = getCameraMatrix(screen_->getVR(), vr::Eye_Right);
+		CHECK(intrinsic(0, 2) < 0 && intrinsic(1, 2) < 0);
+		src_->set("focal_right", intrinsic(0, 0));
+		src_->set("centre_x_right", intrinsic(0, 2));
+		src_->set("centre_y_right", intrinsic(1, 2));
+
 		vr_mode_ = true;
 	}
 	else {
 		vr_mode_ = false;
 		setChannel(Channel::Left); // reset to left channel
+		// todo restore camera params
 	}
 	
 	return vr_mode_;
@@ -335,7 +353,7 @@ bool ftl::gui::Camera::thumbnail(cv::Mat &thumb) {
 	cv::flip(thumb, thumb, 0);
 	return true;
 }
-#include <math.h>
+
 const GLTexture &ftl::gui::Camera::captureFrame() {
 	float now = (float)glfwGetTime();
 	delta_ = now - ftime_;
@@ -343,7 +361,7 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 
 	if (src_ && src_->isReady()) {
 		UNIQUE_LOCK(mutex_, lk);
-		
+
 		if (isVR()) {
 			#ifdef HAVE_OPENVR
 			vr::VRCompositor()->WaitGetPoses(rTrackedDevicePose_, vr::k_unMaxTrackedDeviceCount, NULL, 0 );
@@ -353,54 +371,46 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 				Eigen::Matrix4d eye_l = ConvertSteamVRMatrixToMatrix4(
 					vr::VRSystem()->GetEyeToHeadTransform(vr::Eye_Left));
 				
-				// assumes eye_l(3, 0) = -eye_r(3, 0)
-				// => baseline = abs(2*eye_l(3, 0))
-				float baseline_in = 2.0 * -eye_l(0, 3);
+				Eigen::Matrix4d eye_r = ConvertSteamVRMatrixToMatrix4(
+					vr::VRSystem()->GetEyeToHeadTransform(vr::Eye_Left));
+
+				float baseline_in = 2.0 * eye_l(0, 3);
+				
 				if (baseline_in != baseline_) {
 					baseline_ = baseline_in;
-					// TODO: update baseline on ftl-reconstruct
+					src_->set("baseline", baseline_);
 				}
-				
 				Eigen::Matrix4d pose = ConvertSteamVRMatrixToMatrix4(rTrackedDevicePose_[vr::k_unTrackedDeviceIndex_Hmd].mDeviceToAbsoluteTracking);
+				Eigen::Vector3d ea = pose.block<3, 3>(0, 0).eulerAngles(0, 1, 2);
 				
-				// translate to L eye
-				Eigen::Translation3d trans(eye_);
-				Eigen::Affine3d t(trans);
-				Eigen::Matrix4d viewPose = t.matrix() * pose;
-
-				// flip rotation (different coordinate axis on OpenGL/ftl)
-				// NOTE: image also flipped!
-
-				Eigen::Vector3d ea = viewPose.block<3, 3>(0, 0).eulerAngles(0, 1, 2);
-				//double rd = 180.0 / M_PI;
-				//LOG(INFO) << "Camera X: " << ea[0] *rd << ", Y: " << ea[1] * rd << ", Z: " << ea[2] * rd;
-
 				// NOTE: If modified, should be verified with VR headset!
 				Eigen::Matrix3d R;
-				R =		Eigen::AngleAxisd(-ea[0], Eigen::Vector3d::UnitX()) *
-						Eigen::AngleAxisd(ea[1], Eigen::Vector3d::UnitY()) *
-						Eigen::AngleAxisd(ea[2], Eigen::Vector3d::UnitZ()); 
-				viewPose.block<3, 3>(0, 0) = R;
-
-				if (src_->hasCapabilities(ftl::rgbd::kCapMovable)) src_->setPose(viewPose);
+				R =		Eigen::AngleAxisd(ea[0], Eigen::Vector3d::UnitX()) *
+						Eigen::AngleAxisd(-ea[1], Eigen::Vector3d::UnitY()) *
+						Eigen::AngleAxisd(-ea[2], Eigen::Vector3d::UnitZ()); 
 				
+				//double rd = 180.0 / 3.141592;
+				//LOG(INFO) << "rotation x: " << ea[0] *rd << ", y: " << ea[1] * rd << ", z: " << ea[2] * rd;
+				// pose.block<3, 3>(0, 0) = R;
+				
+				rotmat_.block(0, 0, 3, 3) = R;
+			
 			} else {
 				//LOG(ERROR) << "No VR Pose";
 			}
 			#endif
-		} else {
-			// Lerp the Eye
-			eye_[0] += (neye_[0] - eye_[0]) * lerpSpeed_ * delta_;
-			eye_[1] += (neye_[1] - eye_[1]) * lerpSpeed_ * delta_;
-			eye_[2] += (neye_[2] - eye_[2]) * lerpSpeed_ * delta_;
+		}
 
-			Eigen::Translation3d trans(eye_);
-			Eigen::Affine3d t(trans);
-			Eigen::Matrix4d viewPose = t.matrix() * rotmat_;
+		eye_[0] += (neye_[0] - eye_[0]) * lerpSpeed_ * delta_;
+		eye_[1] += (neye_[1] - eye_[1]) * lerpSpeed_ * delta_;
+		eye_[2] += (neye_[2] - eye_[2]) * lerpSpeed_ * delta_;
 
-			if (src_->hasCapabilities(ftl::rgbd::kCapMovable)) src_->setPose(viewPose);
-		}
+		Eigen::Translation3d trans(eye_);
+		Eigen::Affine3d t(trans);
+		Eigen::Matrix4d viewPose = t.matrix() * rotmat_;
 
+		if (src_->hasCapabilities(ftl::rgbd::kCapMovable)) src_->setPose(viewPose);
+	
 		src_->grab();
 
 		// When switching from right to depth, client may still receive
diff --git a/applications/gui/src/vr.hpp b/applications/gui/src/vr.hpp
index 2a66dfd054c954cdb40b4b8f0159ea1286ff3cfd..7e8f6314fb85765d438ae5f46915a8c215160127 100644
--- a/applications/gui/src/vr.hpp
+++ b/applications/gui/src/vr.hpp
@@ -38,11 +38,11 @@ static inline Eigen::Matrix4d ConvertSteamVRMatrixToMatrix4( const vr::HmdMatrix
 {
 	Eigen::Matrix4d matrixObj;
 	matrixObj <<
-		matPose.m[0][0], matPose.m[0][1], matPose.m[0][2], 0.0,
-		matPose.m[1][0], matPose.m[1][1], matPose.m[1][2], 0.0,
-		matPose.m[2][0], matPose.m[2][1], matPose.m[2][2], 0.0,
-		matPose.m[3][0], matPose.m[3][1], matPose.m[3][2], 1.0f;
-	return matrixObj.transpose();
+		matPose.m[0][0], matPose.m[0][1], matPose.m[0][2], matPose.m[0][3],
+		matPose.m[1][0], matPose.m[1][1], matPose.m[1][2], matPose.m[1][3],
+		matPose.m[2][0], matPose.m[2][1], matPose.m[2][2], matPose.m[2][3],
+					0.0,			 0.0,			  0.0,			   1.0;
+	return matrixObj;
 }
 
 static inline Eigen::Matrix4d ConvertSteamVRMatrixToMatrix4( const vr::HmdMatrix44_t &matPose )
@@ -53,5 +53,5 @@ static inline Eigen::Matrix4d ConvertSteamVRMatrixToMatrix4( const vr::HmdMatrix
 		matPose.m[1][0], matPose.m[1][1], matPose.m[1][2], matPose.m[1][3],
 		matPose.m[2][0], matPose.m[2][1], matPose.m[2][2], matPose.m[2][3],
 		matPose.m[3][0], matPose.m[3][1], matPose.m[3][2], matPose.m[3][3];
-	return matrixObj.transpose();
+	return matrixObj;
 }
\ No newline at end of file
diff --git a/components/codecs/include/ftl/codecs/bitrates.hpp b/components/codecs/include/ftl/codecs/bitrates.hpp
index 8e41b13f7e4d9b77ad38cf23fdb2622d2107a537..976e039fc07b3dd15e7f4ede219ed06c27cff0fe 100644
--- a/components/codecs/include/ftl/codecs/bitrates.hpp
+++ b/components/codecs/include/ftl/codecs/bitrates.hpp
@@ -36,7 +36,9 @@ enum struct definition_t : uint8_t {
 	SD576 = 4,
 	SD480 = 5,
 	LD360 = 6,
-	Any = 7
+	Any = 7,
+
+	HTC_VIVE = 8
 
 	// TODO: Add audio definitions
 };
@@ -66,7 +68,7 @@ enum struct bitrate_t {
  * the best quality and kPreset9 is the worst. The use of presets is useful for
  * adaptive bitrate scenarios where the numbers are increased or decreased.
  */
-typedef uint8_t preset_t;
+typedef int8_t preset_t;
 static const preset_t kPreset0 = 0;
 static const preset_t kPreset1 = 1;
 static const preset_t kPreset2 = 2;
@@ -81,6 +83,8 @@ static const preset_t kPresetBest = 0;
 static const preset_t kPresetWorst = 9;
 static const preset_t kPresetLQThreshold = 4;
 
+static const preset_t kPresetHTCVive = -1;
+
 /**
  * Represents the details of each preset codec configuration.
  */
diff --git a/components/codecs/src/bitrates.cpp b/components/codecs/src/bitrates.cpp
index 519c86712487a8be9285f28392342e6ca6c16713..035e850d1ff20f5e113db2f7004b85c8bbea3040 100644
--- a/components/codecs/src/bitrates.cpp
+++ b/components/codecs/src/bitrates.cpp
@@ -8,6 +8,10 @@ using ftl::codecs::preset_t;
 using ftl::codecs::definition_t;
 using ftl::codecs::codec_t;
 
+static const CodecPreset special_presets[] = {
+	definition_t::HTC_VIVE, definition_t::HTC_VIVE, bitrate_t::High, bitrate_t::High
+};
+
 static const CodecPreset presets[] = {
 	definition_t::HD1080, definition_t::HD1080, bitrate_t::High, bitrate_t::High,
 	definition_t::HD1080, definition_t::HD720, bitrate_t::Standard, bitrate_t::Standard,
@@ -35,7 +39,9 @@ static const Resolution resolutions[] = {
 	1280, 720,		// HD720
 	1024, 576,		// SD576
 	854, 480,		// SD480
-	640, 360		// LD360
+	640, 360,		// LD360
+	0, 0,			// ANY
+	1852, 2056		// HTC_VIVE
 };
 
 int ftl::codecs::getWidth(definition_t d) {
@@ -47,6 +53,7 @@ int ftl::codecs::getHeight(definition_t d) {
 }
 
 const CodecPreset &ftl::codecs::getPreset(preset_t p) {
+	if (p < 0 && p >= -1) return special_presets[std::abs(p+1)];
     if (p > kPresetWorst) return presets[kPresetWorst];
     if (p < kPresetBest) return presets[kPresetBest];
     return presets[p];
diff --git a/components/codecs/src/encoder.cpp b/components/codecs/src/encoder.cpp
index 3ebe40cf91ad75cec92937b013d3215de4104004..fdacc89596668937f8f465995f52f0955bbded01 100644
--- a/components/codecs/src/encoder.cpp
+++ b/components/codecs/src/encoder.cpp
@@ -73,5 +73,6 @@ bool Encoder::encode(const cv::Mat &in, preset_t preset,
 	const auto &settings = ftl::codecs::getPreset(preset);
 	const definition_t definition = (in.type() == CV_32F) ? settings.depth_res : settings.colour_res;
 	const bitrate_t bitrate = (in.type() == CV_32F) ? settings.depth_qual : settings.colour_qual;
+	LOG(INFO) << "Encode definition: " << (int)definition;
 	return encode(in, definition, bitrate, cb);
 }
diff --git a/components/codecs/src/nvpipe_decoder.cpp b/components/codecs/src/nvpipe_decoder.cpp
index bd0273a2747ecd4501a8c755c4cccf1423ba7440..74519a8f2f3b1b5c8e4eb13ea23ff89778402825 100644
--- a/components/codecs/src/nvpipe_decoder.cpp
+++ b/components/codecs/src/nvpipe_decoder.cpp
@@ -62,6 +62,8 @@ bool NvPipeDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
 	is_float_channel_ = is_float_frame;
 	last_definition_ = pkt.definition;
 
+	//LOG(INFO) << "DECODE RESOLUTION: (" << (int)pkt.definition << ") " << ftl::codecs::getWidth(pkt.definition) << "x" << ftl::codecs::getHeight(pkt.definition);
+
 	// Build a decoder instance of the correct kind
 	if (nv_decoder_ == nullptr) {
 		nv_decoder_ = NvPipe_CreateDecoder(
diff --git a/components/codecs/src/nvpipe_encoder.cpp b/components/codecs/src/nvpipe_encoder.cpp
index 1b91c13d083c2bb48a14805d480793a2b3215580..80bde1f9fac0dc63fc68db845b7e53084f6c59ec 100644
--- a/components/codecs/src/nvpipe_encoder.cpp
+++ b/components/codecs/src/nvpipe_encoder.cpp
@@ -72,7 +72,22 @@ void scaleDownAndPad(cv::Mat &in, cv::Mat &out) {
 
 bool NvPipeEncoder::encode(const cv::Mat &in, definition_t odefinition, bitrate_t bitrate, const std::function<void(const ftl::codecs::Packet&)> &cb) {
 	cudaSetDevice(0);
-	auto definition = _verifiedDefinition(odefinition, in);
+	auto definition = odefinition; //_verifiedDefinition(odefinition, in);
+
+	auto width = ftl::codecs::getWidth(definition);
+	auto height = ftl::codecs::getHeight(definition);
+
+	cv::Mat tmp;
+	if (width != in.cols || height != in.rows) {
+		LOG(WARNING) << "Mismatch resolution with encoding resolution";
+		if (in.type() == CV_32F) {
+			cv::resize(in, tmp, cv::Size(width,height), 0.0, 0.0, cv::INTER_NEAREST);
+		} else {
+			cv::resize(in, tmp, cv::Size(width,height));
+		}
+	} else {
+		tmp = in;
+	}
 
 	//LOG(INFO) << "Definition: " << ftl::codecs::getWidth(definition) << "x" << ftl::codecs::getHeight(definition);
 
@@ -80,17 +95,17 @@ bool NvPipeEncoder::encode(const cv::Mat &in, definition_t odefinition, bitrate_
 		LOG(ERROR) << "Missing data for Nvidia encoder";
 		return false;
 	}
-	if (!_createEncoder(in, definition, bitrate)) return false;
+	if (!_createEncoder(tmp, definition, bitrate)) return false;
 
 	//LOG(INFO) << "NvPipe Encode: " << int(definition) << " " << in.cols;
 
-	cv::Mat tmp;
-	if (in.type() == CV_32F) {
-		in.convertTo(tmp, CV_16UC1, 1000);
-	} else if (in.type() == CV_8UC3) {
-		cv::cvtColor(in, tmp, cv::COLOR_BGR2BGRA);
+	//cv::Mat tmp;
+	if (tmp.type() == CV_32F) {
+		tmp.convertTo(tmp, CV_16UC1, 1000);
+	} else if (tmp.type() == CV_8UC3) {
+		cv::cvtColor(tmp, tmp, cv::COLOR_BGR2BGRA);
 	} else {
-		in.copyTo(tmp);
+		//in.copyTo(tmp);
 	}
 
 	// scale/pad to fit output format
diff --git a/components/renderers/cpp/src/splat_render.cpp b/components/renderers/cpp/src/splat_render.cpp
index a7e796dc97d86d65c8f4082beadbd801f3cf9ca0..30c47dc1179018a552d8b083245eac71ba56dae2 100644
--- a/components/renderers/cpp/src/splat_render.cpp
+++ b/components/renderers/cpp/src/splat_render.cpp
@@ -459,32 +459,25 @@ bool Splatter::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
 	{
 		float baseline = camera.baseline;
 		
-		Eigen::Translation3f translation(baseline, 0.0f, 0.0f);
-		LOG(INFO) << translation.vector();
-		Eigen::Affine3f transform(translation);
-		LOG(INFO) << "\n" << transform.matrix();
-		LOG(INFO) << "baseline " << baseline;
-		Eigen::Matrix4f matrix = transform.matrix() * src->getPose().cast<float>();
+		//Eigen::Translation3f translation(baseline, 0.0f, 0.0f);
+		//Eigen::Affine3f transform(translation);
+		//Eigen::Matrix4f matrix = transform.matrix() * src->getPose().cast<float>();
+
+		Eigen::Matrix4f transform = Eigen::Matrix4f::Identity();
+		transform(0, 3) = baseline;
+		Eigen::Matrix4f matrix = transform.inverse() * src->getPose().cast<float>();
+		
 		params.m_viewMatrix = MatrixConversion::toCUDA(matrix.inverse());
 		params.m_viewMatrixInverse = MatrixConversion::toCUDA(matrix);
+
+		params.camera = src->parameters(Channel::Right);
 		
 		out.create<GpuMat>(Channel::Right, Format<uchar4>(camera.width, camera.height));
 		out.get<GpuMat>(Channel::Right).setTo(background_, cvstream);
 
 		_dibr(stream_); // Need to re-dibr due to pose change
 		_renderChannel(out, Channel::Left, Channel::Right, stream_);
-		
-		// renderFrame() expects to render right frame from left as well; Should
-		// possibly add channel_in and channel_out parameters to renderFrame()?
-		// (l/r swap as temporary fix)
-		/*
-		auto &tmp = out.get<GpuMat>(Channel::Left);
-		swap(out.get<GpuMat>(Channel::Right), tmp);
-		_renderChannel(params, out, Channel::Left, stream_);
-		swap(tmp, out.get<GpuMat>(Channel::Right));
-		*/
 
-		_renderChannel(out, Channel::Left, Channel::Right, stream_);
 	} else if (chan != Channel::None) {
 		if (ftl::codecs::isFloatChannel(chan)) {
 			out.create<GpuMat>(chan, Format<float>(camera.width, camera.height));
diff --git a/components/rgbd-sources/src/sources/net/net.cpp b/components/rgbd-sources/src/sources/net/net.cpp
index dd97e961812d186572052ccd44ac5af13678e661..5956114d57bc2b9bc0a0b10bee48fd7a29d6b470 100644
--- a/components/rgbd-sources/src/sources/net/net.cpp
+++ b/components/rgbd-sources/src/sources/net/net.cpp
@@ -107,12 +107,20 @@ bool NetSource::_getCalibration(Universe &net, const UUID &peer, const string &s
 
 				LOG(INFO) << "Calibration received: " << p.cx << ", " << p.cy << ", " << p.fx << ", " << p.fy;
 
-				// Put calibration into config manually
-				host_->getConfig()["focal"] = p.fx;
-				host_->getConfig()["centre_x"] = p.cx;
-				host_->getConfig()["centre_y"] = p.cy;
-				host_->getConfig()["baseline"] = p.baseline;
-				host_->getConfig()["doffs"] = p.doffs;
+				if (chan == Channel::Left) {
+					// Put calibration into config manually
+					host_->getConfig()["focal"] = p.fx;
+					host_->getConfig()["centre_x"] = p.cx;
+					host_->getConfig()["centre_y"] = p.cy;
+					host_->getConfig()["baseline"] = p.baseline;
+					host_->getConfig()["doffs"] = p.doffs;
+				} else {
+					host_->getConfig()["focal_right"] = p.fx;
+					host_->getConfig()["centre_x_right"] = p.cx;
+					host_->getConfig()["centre_y_right"] = p.cy;
+					host_->getConfig()["baseline_right"] = p.baseline;
+					host_->getConfig()["doffs_right"] = p.doffs;
+				}
 				
 				return true;
 			} else {
@@ -138,6 +146,7 @@ NetSource::NetSource(ftl::rgbd::Source *host)
 	temperature_ = host->value("temperature", 6500);
 	default_quality_ = host->value("quality", 0);
 	last_bitrate_ = 0;
+	params_right_.width = 0;
 
 	decoder_c1_ = nullptr;
 	decoder_c2_ = nullptr;
@@ -156,6 +165,16 @@ NetSource::NetSource(ftl::rgbd::Source *host)
 		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/focal", host_->getConfig()["focal"].dump());
 	});
 
+	host->on("centre_x", [this,host](const ftl::config::Event&) {
+		params_.cx = host_->value("centre_x", 0.0);
+		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_x", host_->getConfig()["centre_x"].dump());
+	});
+
+	host->on("centre_y", [this,host](const ftl::config::Event&) {
+		params_.cy = host_->value("centre_y", 0.0);
+		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_y", host_->getConfig()["centre_y"].dump());
+	});
+
 	host->on("doffs", [this,host](const ftl::config::Event&) {
 		params_.doffs = host_->value("doffs", params_.doffs);
 		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/doffs", host_->getConfig()["doffs"].dump());
@@ -166,11 +185,25 @@ NetSource::NetSource(ftl::rgbd::Source *host)
 		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/baseline", host_->getConfig()["baseline"].dump());
 	});
 
-	host->on("doffs", [this,host](const ftl::config::Event&) {
-		params_.doffs = host_->value("doffs", params_.doffs);
-		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/doffs", host_->getConfig()["doffs"].dump());
+	// Right parameters
+
+	host->on("focal_right", [this,host](const ftl::config::Event&) {
+		params_right_.fx = host_->value("focal_right", 0.0);
+		params_right_.fy = params_right_.fx;
+		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/focal_right", host_->getConfig()["focal_right"].dump());
+	});
+
+	host->on("centre_x_right", [this,host](const ftl::config::Event&) {
+		params_right_.cx = host_->value("centre_x_right", 0.0);
+		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_x_right", host_->getConfig()["centre_x_right"].dump());
 	});
 
+	host->on("centre_y_right", [this,host](const ftl::config::Event&) {
+		params_right_.cy = host_->value("centre_y_right", 0.0);
+		host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_y_right", host_->getConfig()["centre_y_right"].dump());
+	});
+
+
 	host->on("quality", [this,host](const ftl::config::Event&) {
 		default_quality_ = host->value("quality", 0);
 	});
@@ -356,12 +389,13 @@ void NetSource::setPose(const Eigen::Matrix4d &pose) {
 
 ftl::rgbd::Camera NetSource::parameters(ftl::codecs::Channel chan) {
 	if (chan == ftl::codecs::Channel::Right) {
-		auto uri = host_->get<string>("uri");
-		if (!uri) return params_;
+		if (params_right_.width == 0) {
+			auto uri = host_->get<string>("uri");
+			if (!uri) return params_;
 
-		ftl::rgbd::Camera params;
-		_getCalibration(*host_->getNet(), peer_, *uri, params, chan);
-		return params;
+			_getCalibration(*host_->getNet(), peer_, *uri, params_right_, chan);
+		}
+		return params_right_;
 	} else {
 		return params_;
 	}
@@ -386,6 +420,7 @@ void NetSource::_updateURI() {
 		peer_ = *p;
 
 		has_calibration_ = _getCalibration(*host_->getNet(), peer_, *uri, params_, ftl::codecs::Channel::Left);
+		_getCalibration(*host_->getNet(), peer_, *uri, params_right_, ftl::codecs::Channel::Right);
 
 		host_->getNet()->bind(*uri, [this](short ttimeoff, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) {
 			//if (chunk == -1) {
diff --git a/components/rgbd-sources/src/sources/net/net.hpp b/components/rgbd-sources/src/sources/net/net.hpp
index 0f867a9ab08fee843ba229ba47636938ef04abfa..469902a5709f1ce9674d4fcafb0b36b957b5f7a4 100644
--- a/components/rgbd-sources/src/sources/net/net.hpp
+++ b/components/rgbd-sources/src/sources/net/net.hpp
@@ -58,6 +58,7 @@ class NetSource : public detail::Source {
 	int maxN_;
 	int default_quality_;
 	ftl::codecs::Channel prev_chan_;
+	ftl::rgbd::Camera params_right_;
 
 	ftl::rgbd::detail::ABRController abr_;
 	int last_bitrate_;
diff --git a/components/rgbd-sources/src/sources/virtual/virtual.cpp b/components/rgbd-sources/src/sources/virtual/virtual.cpp
index afea7e17c485b7a1a6ae050c02e61372bb5d4604..17ce33638fbc1cfc934beb93243399cf93151118 100644
--- a/components/rgbd-sources/src/sources/virtual/virtual.cpp
+++ b/components/rgbd-sources/src/sources/virtual/virtual.cpp
@@ -3,12 +3,26 @@
 using ftl::rgbd::VirtualSource;
 using ftl::rgbd::Source;
 using ftl::codecs::Channel;
+using ftl::rgbd::Camera;
 
 class VirtualImpl : public ftl::rgbd::detail::Source {
 	public:
 	explicit VirtualImpl(ftl::rgbd::Source *host, const ftl::rgbd::Camera &params) : ftl::rgbd::detail::Source(host) {
 		params_ = params;
+
+		params_right_.width = host->value("width", 1280);
+		params_right_.height = host->value("height", 720);
+		params_right_.fx = host->value("focal_right", 700.0f);
+		params_right_.fy = params_right_.fx;
+		params_right_.cx = host->value("centre_x_right", -(double)params_.width / 2.0);
+		params_right_.cy = host->value("centre_y_right", -(double)params_.height / 2.0);
+		params_right_.minDepth = host->value("minDepth", 0.1f);
+		params_right_.maxDepth = host->value("maxDepth", 20.0f);
+		params_right_.doffs = 0;
+		params_right_.baseline = host->value("baseline", 0.0f);
+
 		capabilities_ = ftl::rgbd::kCapVideo | ftl::rgbd::kCapStereo;
+
 		if (!host->value("locked", false)) capabilities_ |= ftl::rgbd::kCapMovable;
 		host->on("baseline", [this](const ftl::config::Event&) {
 			params_.baseline = host_->value("baseline", 0.0f);
@@ -19,6 +33,27 @@ class VirtualImpl : public ftl::rgbd::detail::Source {
 			params_.fy = params_.fx;
 		});
 
+		host->on("centre_x", [this](const ftl::config::Event&) {
+			params_.cx = host_->value("centre_x", 0.0f);
+		});
+
+		host->on("centre_y", [this](const ftl::config::Event&) {
+			params_.cy = host_->value("centre_y", 0.0f);
+		});
+
+		host->on("focal_right", [this](const ftl::config::Event&) {
+			params_right_.fx = host_->value("focal_right", 700.0f);
+			params_right_.fy = params_right_.fx;
+		});
+
+		host->on("centre_x_right", [this](const ftl::config::Event&) {
+			params_right_.cx = host_->value("centre_x_right", 0.0f);
+		});
+
+		host->on("centre_y_right", [this](const ftl::config::Event&) {
+			params_right_.cy = host_->value("centre_y_right", 0.0f);
+		});
+
 	}
 
 	~VirtualImpl() {
@@ -65,14 +100,32 @@ class VirtualImpl : public ftl::rgbd::detail::Source {
 		return true;
 	}
 
+	Camera parameters(ftl::codecs::Channel c) {
+		return (c == Channel::Left) ? params_ : params_right_;
+	}
+
 	bool isReady() override { return true; }
 
 	std::function<void(ftl::rgbd::Frame &)> callback;
 	ftl::rgbd::Frame frame;
+
+	ftl::rgbd::Camera params_right_;
 };
 
 VirtualSource::VirtualSource(ftl::config::json_t &cfg) : Source(cfg) {
 	auto params = params_;
+
+	params_.width = value("width", 1280);
+	params_.height = value("height", 720);
+	params_.fx = value("focal", 700.0f);
+	params_.fy = params_.fx;
+	params_.cx = value("centre_x", -(double)params_.width / 2.0);
+	params_.cy = value("centre_y", -(double)params_.height / 2.0);
+	params_.minDepth = value("minDepth", 0.1f);
+	params_.maxDepth = value("maxDepth", 20.0f);
+	params_.doffs = 0;
+	params_.baseline = value("baseline", 0.0f);
+
 	impl_ = new VirtualImpl(this, params);
 }
 
diff --git a/components/rgbd-sources/src/streamer.cpp b/components/rgbd-sources/src/streamer.cpp
index c446445c9566f8b3560fc9b8f0b4123eaa427fa2..939252d77a6704bf7c9c5a2202ec72a6c45562a8 100644
--- a/components/rgbd-sources/src/streamer.cpp
+++ b/components/rgbd-sources/src/streamer.cpp
@@ -127,6 +127,20 @@ Streamer::Streamer(nlohmann::json &config, Universe *net)
 	//net->bind("ping_streamer", [this](unsigned long long time) -> unsigned long long {
 	//	return time;
 	//});
+
+	on("hq_bitrate", [this](const ftl::config::Event &e) {
+		UNIQUE_LOCK(mutex_,ulk);
+		for (auto &s : sources_) {
+			s.second->hq_bitrate = value("hq_bitrate", ftl::codecs::kPresetBest);
+		}
+	});
+
+	on("lq_bitrate", [this](const ftl::config::Event &e) {
+		UNIQUE_LOCK(mutex_,ulk);
+		for (auto &s : sources_) {
+			s.second->lq_bitrate = value("lq_bitrate", ftl::codecs::kPresetWorst);
+		}
+	});
 }
 
 Streamer::~Streamer() {
@@ -166,6 +180,10 @@ void Streamer::add(Source *src) {
 		s->clientCount = 0;
 		s->hq_count = 0;
 		s->lq_count = 0;
+
+		s->hq_bitrate = value("hq_bitrate", ftl::codecs::kPresetBest);
+		s->lq_bitrate = value("lq_bitrate", ftl::codecs::kPresetWorst);
+
 		sources_[src->getID()] = s;
 
 		group_.addSource(src);