diff --git a/libraries/FastSerial/FastSerial.cpp b/libraries/FastSerial/FastSerial.cpp
index efc8c896e6d14d66113e7083fe396c572540221f..67f71483c6f71a254e7a44abf73ec14988afe27e 100644
--- a/libraries/FastSerial/FastSerial.cpp
+++ b/libraries/FastSerial/FastSerial.cpp
@@ -212,6 +212,13 @@ size_t FastSerial::write(uint8_t c)
 
 	// wait for room in the tx buffer
 	i = (_txBuffer->head + 1) & _txBuffer->mask;
+
+	// if the port is set into non-blocking mode, then drop the byte
+	// if there isn't enough room for it in the transmit buffer
+	if (_nonblocking_writes && i == _txBuffer->tail) {
+		return 0;
+	}
+
 	while (i == _txBuffer->tail)
 		;
 
diff --git a/libraries/FastSerial/FastSerial.h b/libraries/FastSerial/FastSerial.h
index 5fcaa95c751a2acf50b30e34fd4682ea06479ec1..b64ff1fb2d3dddbde1402197bd88ca8681516d11 100644
--- a/libraries/FastSerial/FastSerial.h
+++ b/libraries/FastSerial/FastSerial.h
@@ -160,6 +160,11 @@ public:
 		return (1<<port) & _serialInitialized;
 	}
 
+	// ask for writes to be blocking or non-blocking
+	void set_blocking_writes(bool blocking) {
+		_nonblocking_writes = !blocking;
+	}
+
 private:
 
 	/// Bit mask for initialized ports
@@ -187,6 +192,10 @@ private:
 	Buffer			* const _txBuffer;
 	bool 			_open;
 
+	// whether writes to the port should block waiting
+	// for enough space to appear
+	bool			_nonblocking_writes;
+
 	/// Allocates a buffer of the given size
 	///
 	/// @param	buffer		The buffer descriptor for which the buffer will