diff --git a/groundStation/src/backend/packet.c b/groundStation/src/backend/packet.c
index 7ddbb536321603a819f7af2c6195636e8a1aba52..abcb42490b177873964cf0715270a87b7a6087d0 100644
--- a/groundStation/src/backend/packet.c
+++ b/groundStation/src/backend/packet.c
@@ -14,7 +14,7 @@ ssize_t EncodePacket(
         const struct metadata * m,  /* Metadata to encode */
         const uint8_t * data)       /* Data to encode */
 {
-	if (packet_size < (HDR_SIZE + CSUM_SIZE + m->data_len)) {
+	if (packet_size < (size_t)(HDR_SIZE + CSUM_SIZE + m->data_len)) {
 		return -1;
 	}
 
@@ -58,7 +58,7 @@ ssize_t DecodePacket(
 	m->msg_id = BytesTo16(packet[ID_L], packet[ID_H]);
 	m->data_len =  BytesTo16(packet[DLEN_L], packet[DLEN_H]);
 
-	if (packet_size < (HDR_SIZE + CSUM_SIZE + m->data_len)) {
+	if (packet_size < (size_t)(HDR_SIZE + CSUM_SIZE + m->data_len)) {
 		return -3;
 	}
 
diff --git a/groundStation/src/backend/packet.h b/groundStation/src/backend/packet.h
index 87f8c5c7e73ef23bbd9bbc7befb3d5c897ad3b57..316432797b9fe820e9cb8603f022e45411e63af4 100644
--- a/groundStation/src/backend/packet.h
+++ b/groundStation/src/backend/packet.h
@@ -4,6 +4,8 @@
 #include <stdint.h>
 #include <sys/types.h>
 
+#include "commands.h"
+
 enum PacketHeader {
 	BEGIN,
 	MTYPE_L,
@@ -19,11 +21,6 @@ enum ChecksumFormat {
 	CSUM_L,
 	CSUM_SIZE
 };
-struct metadata {
-	int msg_type;
-	int msg_id;
-	size_t data_len;
-};
 
 /* Combine metadata and data to form a wire-sendable packet.
  * Returns the size of the encoded packet 
diff --git a/groundStation/src/backend/type_def.h b/groundStation/src/backend/type_def.h
deleted file mode 100644
index 27b5d192e5538c326668b45785d0be62028e0ee8..0000000000000000000000000000000000000000
--- a/groundStation/src/backend/type_def.h
+++ /dev/null
@@ -1,360 +0,0 @@
-/*
- * struct_def.h
- *
- *  Created on: Mar 2, 2016
- *      Author: ucart
- */
-
-#ifndef __TYPE_DEF_H
-#define __TYPE_DEF_H
-
-/**
- * @brief
- *      The modes for autonomous and manual flight.
- *
- */
-enum flight_mode{
-	AUTO_FLIGHT_MODE,
-	MANUAL_FLIGHT_MODE
-};
-
-//----------------------------------------------------------------------------------------------
-//     index||     0    |     1    |      2      |  3 & 4 |      5 & 6       |  7+  |   end    |
-//---------------------------------------------------------------------------------------------|
-// msg param|| beg char | msg type | msg subtype | msg id | data len (bytes) | data | checksum |
-//-------------------------------------------------------------------------------------------- |
-//     bytes||     1    |     1    |      1      |    2   |        2         | var  |    1     |
-//----------------------------------------------------------------------------------------------
-typedef struct {
-	char begin_char;
-	int msg_type;
-	int msg_id;
-	int data_len;
-} metadata_t;
-
-
-// String builder data type
-typedef struct stringBuilder_s {
-	char* buf;
-	int length;
-	int capacity;
-	int maxCapacity;
-
-	// Methods
-	int (*addStr)(struct stringBuilder_s*, char*);
-	int (*addStrAt)(struct stringBuilder_s*, char*, int);
-	int (*addChar)(struct stringBuilder_s*, char);
-	int (*addCharAt)(struct stringBuilder_s*, char, int);
-	int (*removeCharAt)(struct stringBuilder_s*, int);
-	void (*clear)(struct stringBuilder_s*);
-} stringBuilder_t;
-
-typedef struct {
-	char** tokens;
-	int numTokens;
-} tokenList_t;
-
-typedef struct commands{
-	int pitch, roll, yaw, throttle;
-}commands;
-
-typedef struct raw{
-	int x,y,z;
-}raw;
-typedef struct PID_Consts{
-	float P, I, D;
-}PID_Consts;
-
-//Camera system info
-typedef struct {
-	int packetId;
-
-	double y_pos;
-	double x_pos;
-	double alt_pos;
-
-	double yaw;
-	double roll;
-	double pitch;
-} quadPosition_t;
-
-typedef struct {
-	float yaw;
-	float roll;
-	float pitch;
-	float throttle;
-} quadTrims_t;
-
-//Gyro, accelerometer, and magnetometer data structure
-//Used for reading an instance of the sensor data
-typedef struct {
-
-	// GYRO
-	//Xint16 raw_gyro_x, raw_gyro_y, raw_gyro_z;
-
-	float gyro_xVel_p; // In degrees per second
-	float gyro_yVel_q;
-	float gyro_zVel_r;
-
-	// ACCELEROMETER
-	//Xint16 raw_accel_x, raw_accel_y, raw_accel_z;
-
-	float accel_x; //In g
-	float accel_y;
-	float accel_z;
-
-	float accel_roll;
-	float accel_pitch;
-
-
-	// MAG
-	//Xint16 raw_mag_x, raw_mag_y, raw_mag_z;
-
-	float heading; // In degrees
-
-	float mag_x; //Magnetic north: ~50 uT
-	float mag_y;
-	float mag_z;
-
-
-
-}gam_t;
-
-typedef struct PID_t {
-	double current_point;	// Current value of the system
-	double setpoint;		// Desired value of the system
-	float Kp;				// Proportional constant
-	float Ki;				// Integral constant
-	float Kd;				// Derivative constant
-	double prev_error;		// Previous error
-	double acc_error;		// Accumulated error
-	double pid_correction;	// Correction factor computed by the PID
-	float dt; 				// sample period
-} PID_t;
-
-typedef struct PID_values{
-	float P;	// The P component contribution to the correction output
-	float I;	// The I component contribution to the correction output
-	float D;	// The D component contribution to the correction output
-	float error; // the error of this PID calculation
-	float change_in_error; // error change from the previous calc. to this one
-	float pid_correction; // the correction output (P + I + D)
-} PID_values;
-
-///////// MAIN MODULAR STRUCTS
-/**
- * @brief
- *      Holds the data inputed by the user
- *
- */
-typedef struct user_input_t {
-	int rc_commands[6]; 	// Commands from the RC transmitter
-
-
-//	float cam_x_pos;	// Current x position from the camera system
-//	float cam_y_pos;	// Current y position from the camera system
-//	float cam_z_pos;	// Current z position from the camera system
-//	float cam_roll;		// Current roll angle from the camera system
-//	float cam_pitch;	// Current pitch angle from the camera system
-//	float cam_yaw;		// Current yaw angle from the camera system
-
-	float yaw_manual_setpoint;
-	float roll_angle_manual_setpoint;
-	float pitch_angle_manual_setpoint;
-
-	int hasPacket;
-	stringBuilder_t * sb;
-} user_input_t;
-
-/**
- * @brief
- *      Holds the log data to be sent to the ground station. It may hold the
- * timestamp of when a sensor's data was obtained.
- *
- */
-typedef struct log_t {
-	// Time
-	float time_stamp;
-	float time_slice;
-
-	// Id
-	int packetId;
-
-	gam_t gam; 	// Raw and calculated gyro, accel, and mag values are all in gam_t
-	float phi_dot, theta_dot, psi_dot; // gimbal equation values
-
-	quadPosition_t currentQuadPosition;
-
-	float roll_angle_filtered, pitch_angle_filtered;
-	float lidar_altitude;
-
-	float pid_P_component, pid_I_component, pid_D_component; // use these generically for any PID that you are testing
-
-	// PID coefficients and errors
-	PID_t local_x_PID, local_y_PID, altitude_PID;
-	PID_t angle_yaw_PID, angle_roll_PID, angle_pitch_PID;
-	PID_t ang_vel_yaw_PID, ang_vel_roll_PID, ang_vel_pitch_PID;
-
-	PID_values local_x_PID_values, local_y_PID_values, altitude_PID_values;
-	PID_values angle_yaw_PID_values, angle_roll_PID_values, angle_pitch_PID_values;
-	PID_values ang_vel_yaw_PID_values, ang_vel_roll_PID_values, ang_vel_pitch_PID_values;
-
-	// RC commands
-	commands commands;
-
-	//trimmed values
-	quadTrims_t trims;
-
-	int motors[4];
-
-} log_t;
-
-/**
- * @brief
- *      Holds the raw data from the sensors and the timestamp if available
- *
- */
-typedef struct raw_sensor {
-	int acc_x;		// accelerometer x data
-	int acc_x_t;	// time of accelerometer x data
-
-	int acc_y;		// accelerometer y data
-	int acc_y_t;	// time of accelerometer y data
-
-	int acc_z;		// accelerometer z data
-	int acc_z_t;	// time of accelerometer z data
-
-
-	int gyr_x;		// gyroscope x data
-	int gyr_x_t;	// time of gyroscope x data
-
-	int gyr_y;		// gyroscope y data
-	int gyr_y_t;	// time of gyroscope y data
-
-	int gyr_z;		// gyroscope z data
-	int gyr_z_t;	// time of gyroscope z data
-
-	int ldr_z;		//lidar z data (altitude)
-	int ldr_z_t;	//time of lidar z data
-
-	gam_t gam;
-
-	// Structures to hold the current quad position & orientation
-	quadPosition_t currentQuadPosition;
-
-} raw_sensor_t;
-
-/**
- * @brief
- *      Holds the processed data from the sensors and the timestamp if available
- *
- */
-typedef struct sensor {
-	int acc_x;		// accelerometer x data
-	int acc_x_t;	// time of accelerometer x data
-
-	int acc_y;		// accelerometer y data
-	int acc_y_t;	// time of accelerometer y data
-
-	int acc_z;		// accelerometer z data
-	int acc_z_t;	// time of accelerometer z data
-
-
-	int gyr_x;		// gyroscope x data
-	int gyr_x_t;	// time of gyroscope x data
-
-	int gyr_y;		// gyroscope y data
-	int gyr_y_t;	// time of gyroscope y data
-
-	int gyr_z;		// gyroscope z data
-	int gyr_z_t;	// time of gyroscope z data
-
-	int ldr_z;		//lidar z data (altitude)
-	int ldr_z_t;	//time of lidar z data
-
-	float pitch_angle_filtered;
-	float roll_angle_filtered;
-	float lidar_altitude;
-
-	float phi_dot, theta_dot, psi_dot;
-
-	// Structures to hold the current quad position & orientation
-	quadPosition_t currentQuadPosition;
-	quadTrims_t trims;
-
-} sensor_t;
-
-/**
- * @brief
- *      Holds the setpoints to be used in the controller
- *
- */
-typedef struct setpoint_t {
-	quadPosition_t desiredQuadPosition;
-} setpoint_t;
-
-/**
- * @brief
- *      Holds the parameters that are specific to whatever type of
- *      control algorithm is being used
- *
- */
-typedef struct parameter_t {
-	PID_t roll_angle_pid, roll_ang_vel_pid;
-	PID_t pitch_angle_pid, pitch_ang_vel_pid;
-	PID_t yaw_ang_vel_pid;
-	PID_t local_x_pid;
-	PID_t local_y_pid;
-	PID_t yaw_angle_pid;
-	PID_t alt_pid;
-} parameter_t;
-
-/**
- * @brief
- *      Holds user defined data for the controller
- *
- */
-typedef struct user_defined_t {
-	int flight_mode;
-	int engaging_auto;
-} user_defined_t;
-
-/**
- * @brief
- *      Holds the raw actuator values before processing
- *
- */
-typedef struct raw_actuator_t {
-
-	int controller_corrected_motor_commands[6];
-
-} raw_actuator_t;
-
-/**
- * @brief
- *      Holds processed commands to go to the actuators
- *
- */
-typedef struct actuator_command_t {
-	int pwms[4];
-} actuator_command_t;
-
-/**
- * @brief
- * 		Structures to be used throughout
- */
-typedef struct {
-	user_input_t user_input_struct;
-	log_t log_struct;
-	raw_sensor_t raw_sensor_struct;
-	sensor_t sensor_struct;
-	setpoint_t setpoint_struct;
-	parameter_t parameter_struct;
-	user_defined_t user_defined_struct;
-	raw_actuator_t raw_actuator_struct;
-	actuator_command_t actuator_command_struct;
-}modular_structs_t;
-
-//////// END MAIN MODULAR STRUCTS
-
-#endif /* __TYPE_DEF_H */
diff --git a/quad/src/commands/commands.h b/quad/src/commands/commands.h
index 2d41d2e6294c74757518e51b8157df6351765667..194bbaedcb7ac1661035e721da865fc038db8a34 100644
--- a/quad/src/commands/commands.h
+++ b/quad/src/commands/commands.h
@@ -4,6 +4,7 @@
 #include <stdio.h>
 #include <stdlib.h>
 #include <string.h>
+#include <stdint.h>
 
 #define MAX_CMD_TEXT_LENGTH 100
 
@@ -56,7 +57,14 @@ enum MessageTypeID{
 };
 
 struct modular_structs;
-struct metadata;
+
+struct metadata {
+	char begin_char;
+	uint16_t msg_type;
+	uint16_t msg_id;
+	uint16_t data_len;
+};
+
 typedef int (command_cb)(struct modular_structs *, struct metadata *, unsigned char *, unsigned short);
 
 /*
diff --git a/quad/src/quad_app/callbacks.c b/quad/src/quad_app/callbacks.c
index 6ddd546a344df78d637707399cf600472040df53..75e91e6bff28f9a8c74ef0fd22409c6e2c9692c2 100644
--- a/quad/src/quad_app/callbacks.c
+++ b/quad/src/quad_app/callbacks.c
@@ -16,7 +16,7 @@ static size_t total_payload_received = 0;
 /**
   * Currently does nothing.
   */
-int cb_debug(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length)
+int cb_debug(modular_structs_t *structs, struct metadata *meta, u8 *data, u16 length)
 {
 	char buf[255];
 
@@ -33,7 +33,7 @@ int cb_debug(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length)
 /**
   * counts the number of packet logs.
   */
-int cb_packetlog(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) {
+int cb_packetlog(modular_structs_t* structs, struct metadata *meta, u8 *data, u16 length) {
 	n_msg_received += 1;
 	total_payload_received += length;
 	return 0;
@@ -43,11 +43,11 @@ int cb_packetlog(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 len
   * Handles a get packet logs request and sends a response
   * with the packet log data.
   */
-int cb_getpacketlogs(modular_structs_t* structs, metadata_t *meta, u8 *data, u16 length) {
+int cb_getpacketlogs(modular_structs_t* structs, struct metadata *meta, u8 *data, u16 length) {
 	char buf[255];
 
 	// Message logging number of messages received and size of payload received
-	int len = snprintf(buf, sizeof buf, "%d,%d", n_msg_received, total_payload_received);
+	int len = snprintf(buf, sizeof buf, "%d,%lu", n_msg_received, total_payload_received);
 
 	send_data(&structs->hardware_struct.uart, LOG_ID, 0, buf, len >= sizeof(buf) ? 255 : len + 1);
 	return 0;
@@ -56,7 +56,7 @@ int cb_getpacketlogs(modular_structs_t* structs, metadata_t *meta, u8 *data, u16
 /*
  * Handles receiving new location updates.
  */
-int cb_update(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length)
+int cb_update(modular_structs_t *structs, struct metadata *meta, u8 *data, u16 length)
 {
 	//processUpdate(packet, &(structs->raw_sensor_struct.currentQuadPosition));
 
@@ -94,7 +94,7 @@ int cb_update(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length
 /**
   * This is called on the ground station to begin sending VRPN to the quad.
   */
-int cb_beginupdate(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length) {
+int cb_beginupdate(modular_structs_t *structs, struct metadata *meta, u8 *data, u16 length) {
 	structs->user_input_struct.receivedBeginUpdate = 1;
 	return 0;
 }
@@ -137,7 +137,7 @@ struct node_ids get_node_ids(u8 *data) {
   * 
   * Does not send anything in response.
   */
-int cb_setparam(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 length)
+int cb_setparam(modular_structs_t *structs, struct metadata *meta, u8 *data, u16 length)
 {
 	// Check if the data length is correct
 	if (length != 8) {return -1;}
@@ -176,7 +176,7 @@ int cb_setparam(modular_structs_t *structs, metadata_t *meta, u8 *data, u16 leng
   * |       bytes ||      2      |      2      |      4      |
   * |--------------------------------------------------------|
   */
-int cb_getparam(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 length)
+int cb_getparam(modular_structs_t* structs, struct metadata *meta,  u8 *data, u16 length)
 {
 	// Check if the data length is correct
 	if (length != 4) {return -1;}
@@ -199,7 +199,7 @@ int cb_getparam(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 len
 	// Send the response
 	send_data(&structs->hardware_struct.uart, RESPPARAM_ID, msg_id, resp_data, sizeof(resp_data));
 
-	return 0;
+	return 5;
 }
 
 /**
@@ -217,7 +217,7 @@ int cb_getparam(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 len
   * 
   * Does not send anything in response.
   */
-int cb_setsource(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 length) {
+int cb_setsource(modular_structs_t* structs, struct metadata *meta,  u8 *data, u16 length) {
 	if (length != 8) {return -1;}
 	int16_t dest_node = build_short(data);
 	int16_t dest_input = build_short(data + 2);
@@ -254,7 +254,7 @@ int cb_setsource(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 le
   * |       bytes ||       2      |       2       |      2      |       2       |
   * |---------------------------------------------------------------------------|
   */
-int cb_getsource(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 length) {
+int cb_getsource(modular_structs_t* structs, struct metadata *meta,  u8 *data, u16 length) {
 	if (length != 4) {return -1;}
 	u16 msg_id = meta->msg_id;
 	// Get requested IDs
@@ -276,7 +276,7 @@ int cb_getsource(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 le
   * Handles a command to get a node output value from the quad.
   * Packet structure is the same as getparam
   */
-int cb_getoutput(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 length)
+int cb_getoutput(modular_structs_t* structs, struct metadata *meta,  u8 *data, u16 length)
 {
 	// Check if the data length is correct
 	if (length != 4) {return -1;}
@@ -315,7 +315,7 @@ int cb_getoutput(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 le
  * |       bytes ||     2*N     |      2*N       |      < 4096     |
  * |---------------------------------------------------------------|
  */
-int cb_getnodes(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 length) {
+int cb_getnodes(modular_structs_t* structs, struct metadata *meta,  u8 *data, u16 length) {
 	const struct computation_graph* graph = structs->parameter_struct.graph;
 	if (graph->n_nodes >= 150) {
 		static char* error_msg = "Over 150 nodes. Not responding to cb_getnodes for fear of buffer overflow.";
@@ -381,7 +381,7 @@ int cb_getnodes(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 len
  * |       bytes ||       2      |
  * |-----------------------------|
  */
-int cb_addnode(modular_structs_t* structs, metadata_t *meta,  u8 *data, u16 length) {
+int cb_addnode(modular_structs_t* structs, struct metadata *meta,  u8 *data, u16 length) {
 	if (length < 2) {return -1;}
 	// Size of name
 	size_t name_len = length - 2;
diff --git a/quad/src/quad_app/callbacks.h b/quad/src/quad_app/callbacks.h
index 3a13626dbd13e8c3d5bba48cf6c4675069e96394..7642fd1624fb5563535c2d03b0ea448e4a6ef1c2 100644
--- a/quad/src/quad_app/callbacks.h
+++ b/quad/src/quad_app/callbacks.h
@@ -1,9 +1,9 @@
 #ifndef __callbacks_h
 #define __callbacks_h
 
+#include "commands.h"
 /* Grab some stupid stuff from legacy code */
 struct modular_structs;
-struct metadata;
 typedef int (command_cb)(struct modular_structs *, struct metadata *, unsigned char *, unsigned short);
 
 #endif
diff --git a/quad/src/quad_app/communication.c b/quad/src/quad_app/communication.c
index c0d37659e29c0b8145b00e15f9a3302e2ef343ae..32b1e3da08d080c3ea43f8ccbea34dbcbdb13c0d 100644
--- a/quad/src/quad_app/communication.c
+++ b/quad/src/quad_app/communication.c
@@ -22,7 +22,6 @@ u8 packet[MAX_PACKET_SIZE];
 int bytes_recv = 0;
 
 int try_receive_packet(struct UARTDriver *uart) {
-
   int attempts = 0;
   while (attempts++ < MAX_PACKET_SIZE) {
     // Find start of packet
@@ -77,7 +76,7 @@ int try_receive_packet(struct UARTDriver *uart) {
 }
 
 int process_packet(modular_structs_t *structs) {
-  metadata_t meta;
+  struct metadata meta;
   // parse metadata
   meta.begin_char = packet[0];
   meta.msg_type = packet[2] << 8 | packet[1];
diff --git a/quad/src/quad_app/quad_app.c b/quad/src/quad_app/quad_app.c
index 22829b5c8d2a6e5247a670f348c4ecad03dc6473..49386e9b9a689e99b979dafab743a4e3e57125e3 100644
--- a/quad/src/quad_app/quad_app.c
+++ b/quad/src/quad_app/quad_app.c
@@ -59,7 +59,6 @@ int quad_main(int (*setup_hardware)(hardware_t *hardware_struct))
 		usleep(500000);
 		u32 start_time = timer_get_count();
 #endif
-
 		process_received(&structs);
 
 #ifdef UART_BENCHMARK
diff --git a/quad/src/quad_app/type_def.h b/quad/src/quad_app/type_def.h
index 8d6363cfa70c9eeff3bb0aa8dbac7cafefd466a1..53af7f2f873cd25c07ac4f25ac6127e33a35c768 100644
--- a/quad/src/quad_app/type_def.h
+++ b/quad/src/quad_app/type_def.h
@@ -38,13 +38,6 @@ enum flight_mode{
 //-------------------------------------------------------------------------------------------- |
 //     bytes||     1    |          2             |    2   |        2         | var  |    1     |
 //----------------------------------------------------------------------------------------------
-typedef struct {
-	char begin_char;
-	uint16_t msg_type;
-	uint16_t msg_id;
-	uint16_t data_len;
-} metadata_t;
-
 
 typedef struct {
 	char** tokens;
diff --git a/quad/src/virt_quad/hw_impl_unix_uart.c b/quad/src/virt_quad/hw_impl_unix_uart.c
index c4f024ff282e6038f4ef63bd88a615fc14e9673f..9d1001ee2fd413626f374aa20ad612364f572891 100644
--- a/quad/src/virt_quad/hw_impl_unix_uart.c
+++ b/quad/src/virt_quad/hw_impl_unix_uart.c
@@ -51,8 +51,9 @@ int unix_uart_reset(struct UARTDriver *self) {
 }
 
 int unix_uart_write(struct UARTDriver *self, unsigned char c) {
-	return send(client, &c, 1, MSG_DONTWAIT);
-	// return write(client, &c, 1);
+	printf("sending [%c]\n", c);
+	send(client, &c, 1, MSG_DONTWAIT);
+	return 0;
 }
 
 int unix_uart_read(struct UARTDriver *self, unsigned char *c) {
@@ -61,10 +62,10 @@ int unix_uart_read(struct UARTDriver *self, unsigned char *c) {
 	
 	if (bytes_available > 0) {
 		int bytes = recv(client, c, 1, 0);
-		printf("read in %d byte [%x]\n", bytes, *c);
-		return bytes;
-	} else {
+		printf("read in %d byte [%X]\n", bytes, *c);
 		return 0;
+	} else {
+		return 1;
 	}
 	
 }
\ No newline at end of file