Added initial libusb driver.  This needs to be modified to build under GYP and with AOS.
diff --git a/gyro_board/src/libusb-driver/Makefile b/gyro_board/src/libusb-driver/Makefile
new file mode 100644
index 0000000..707fa0c
--- /dev/null
+++ b/gyro_board/src/libusb-driver/Makefile
@@ -0,0 +1,15 @@
+SRCS = get.cc libusb_wrap.cc signal_handler.cc thread.cc
+CFLAGS  = -I./ -I/usr/include/libusb-1.0 -g -std=gnu++0x
+LDFLAGS = -g -lgflags -lglog -lusb-1.0 -lboost_thread-mt -lrt
+
+get: $(SRCS:.cc=.o)
+	g++ $^ -o $@ $(LDFLAGS)
+
+%.o: %.cc
+	g++ -MMD -MP -c $(CFLAGS) $< -o $@
+
+clean:
+	$(RM) $(SRCS:.cc=.o) $(SRCS:.cc=.d) get
+
+.PHONY: clean
+-include $(SRCS:.cc=.d)
diff --git a/gyro_board/src/libusb-driver/README b/gyro_board/src/libusb-driver/README
new file mode 100644
index 0000000..f8c3657
--- /dev/null
+++ b/gyro_board/src/libusb-driver/README
@@ -0,0 +1 @@
+./get --logtostderr=1
diff --git a/gyro_board/src/libusb-driver/get.cc b/gyro_board/src/libusb-driver/get.cc
new file mode 100644
index 0000000..5922958
--- /dev/null
+++ b/gyro_board/src/libusb-driver/get.cc
@@ -0,0 +1,235 @@
+#include "get.h"
+
+#include <google/gflags.h>
+#include <glog/logging.h>
+#include <iostream>
+#include <signal.h>
+#include <stdio.h>
+#include <queue>
+#include <unistd.h>
+#include <map>
+
+#include "signal_handler.h"
+
+DEFINE_int32(vid, 0x1424, "Vendor ID of the device.");
+DEFINE_int32(pid, 0xd243, "Product ID of the device.");
+DEFINE_bool(send, true,
+            "True if the code should send packets.  (default: true)");
+
+// USB descriptors in use:
+// 0x81 Interrupt IN endpoint with the received CAN packets.
+//      These packets are 64 bytes maximum, and have the same format as
+//      SocketCAN.
+// 0x04 Interrupt OUT endpoint with the CAN packets to send.
+//      These packets are 64 bytes maximum, and have the same format as
+//      SocketCAN.
+// 0x82 Bulk IN endpoint with printf output.
+// 0x05 Bulk OUT endpoint for stdin.
+
+bool can_frame_priority_comparator::operator() (
+    const struct can_frame& x,
+    const struct can_frame& y) const {
+  // Error frames win first.
+  if (x.can_id & CAN_EFF_FLAG) {
+    return false;
+  }
+  if (y.can_id & CAN_EFF_FLAG) {
+    return true;
+  }
+  // Extended frames send the first 11 bits out just like a standard frame.
+  int x_standard_bits = (x.can_id & CAN_SFF_MASK);
+  int y_standard_bits = (y.can_id & CAN_SFF_MASK);
+  if (x_standard_bits == y_standard_bits) {
+    // RTR wins next.
+    bool x_rtr = (x.can_id & CAN_RTR_FLAG);
+    bool y_rtr = (y.can_id & CAN_RTR_FLAG);
+    if (x_rtr == y_rtr) {
+      // Now check if it is an EFF packet.
+      bool x_eff = (x.can_id & CAN_EFF_FLAG);
+      bool y_eff = (y.can_id & CAN_EFF_FLAG);
+      if (x_eff == y_eff) {
+        // Now compare the bits in the extended frame.
+        return (x.can_id & CAN_EFF_MASK) < (y.can_id & CAN_EFF_MASK);
+      } else if (x_eff < y_eff) {
+        return false;
+      } else {
+        return true;
+      }
+    } else if (x_rtr < y_rtr) {
+      return true;
+    } else {
+      return false;
+    }
+  } else {
+    return x_standard_bits < y_standard_bits;
+  }
+}
+
+class GyroDriver::PacketReceiver : public Thread {
+ public:
+  // refusing to send any more frames.
+  static const int kMaxRXFrames = 128;
+
+  explicit PacketReceiver(LibUSBDeviceHandle *dev_handle)
+      : Thread(), dev_handle_(dev_handle), rx_queue_(new can_priority_queue) {}
+
+  // Serve.
+  void operator()();
+
+  bool GetCanFrame(struct can_frame *msg);
+
+ private:
+  typedef std::priority_queue<struct can_frame,
+                              std::vector<struct can_frame>,
+                              can_frame_priority_comparator> can_priority_queue;
+
+  LibUSBDeviceHandle *dev_handle_;
+  boost::mutex rx_mutex_;
+  std::unique_ptr<can_priority_queue> rx_queue_;
+  //boost::condition_variable rx_cond_;
+};
+
+GyroDriver::GyroDriver(LibUSBDeviceHandle *dev_handle)
+    : dev_handle_(dev_handle), dbg_(new DbgReader(this)),
+    debug_thread_(new boost::thread(boost::ref(*dbg_))),
+    rx_(new GyroDriver::PacketReceiver(dev_handle)),
+    rx_thread_(new boost::thread(boost::ref(*rx_))) { }
+
+
+std::string GyroDriver::GetDebugData() {
+  char data[64];
+  int r;
+  int transferred;
+  r = dev_handle_->bulk_transfer(0x82,
+      (unsigned char *)data, sizeof(data),
+      &transferred, 0);
+  return std::string(data, transferred);
+}
+
+void GyroDriver::Terminate() {
+  rx_->Terminate();
+}
+
+GyroDriver::~GyroDriver() {
+  rx_->Terminate();
+  rx_thread_->join();
+  dbg_->Terminate();
+  debug_thread_->join();
+}
+
+//bool GyroDriver::GetCanFrame(struct can_frame *msg) {
+//  return rx_->GetCanFrame(msg);
+//}
+
+struct DataStruct{
+	int64_t gyro_angle;
+
+	int32_t right_drive;
+	int32_t left_drive;
+	int32_t shooter_angle;
+	int32_t shooter;
+	int32_t indexer;
+	int32_t wrist;
+
+	int32_t capture_top_rise;
+	int32_t capture_top_fall;
+	int32_t capture_bottom_fall_delay;
+	int32_t capture_wrist_rise;
+	int32_t capture_shooter_angle_rise;
+
+	int8_t  top_rise_count;
+
+	int8_t top_fall_count;
+
+	int8_t bottom_rise_count;
+
+	int8_t bottom_fall_delay_count;
+	int8_t bottom_fall_count;
+
+	int8_t wrist_rise_count;
+
+	int8_t shooter_angle_rise_count;
+} __attribute__((__packed__));
+
+void GyroDriver::PacketReceiver::operator()() {
+  	int r;
+  	int actual;
+  	uint8_t data[64];
+  DataStruct *real_data;
+  real_data = (DataStruct *)data;
+  
+  while (should_run()) {
+    r = dev_handle_->interrupt_transfer(
+        0x81, data, sizeof(data), &actual, 1000);
+    printf("size: %d\n",sizeof(DataStruct));
+    CHECK_GT(actual, 0);
+    
+    if (r != 0) {
+      LOG(ERROR) << "Read Error.  Read " << actual;
+    }
+    
+    printf("angle: %d\n", real_data->gyro_angle);
+    printf("drivel: %d\n", real_data->left_drive);
+    printf("driver: %d\n", real_data->right_drive);
+    printf("shooter: %d\n", real_data->shooter);
+    printf("shooter_angle: %d\n", real_data->shooter_angle);
+    printf("indexer: %d\n", real_data->indexer);
+    printf("wrist: %d\n", real_data->wrist);
+    printf("capture:\n");
+    printf("  wrist_rise{%d}: %d\n", real_data->wrist_rise_count, 
+    		    real_data->capture_wrist_rise);
+    printf("  shooter_angle_rise{%d}: %d\n", real_data->shooter_angle_rise_count,
+    		    real_data->capture_shooter_angle_rise);
+    printf("  bottom_rise_delay{%d}; \n", real_data->bottom_rise_count);
+    printf("  bottom_fall_delay{%d,%d}: %d\n", real_data->bottom_fall_count,
+    		    real_data->bottom_fall_delay_count,
+    		    real_data->capture_bottom_fall_delay);
+    printf("  top_rise{%d}: %d\n", real_data->top_rise_count,
+    		    real_data->capture_top_rise);
+    printf("  top_fall{%d}: %d\n", real_data->top_fall_count,
+    		    real_data->capture_top_fall);
+
+
+
+
+    //if (actual > 1) {
+    //  rx_cond_.notify_all();
+    //}
+  }
+  //rx_cond_.notify_all();
+  LOG(INFO) << "Receive thread down.";
+}
+
+DbgReader::DbgReader(GyroDriver *gyro)
+    : Thread(), gyro_(gyro) {}
+
+void DbgReader::operator()() {
+  unsigned char data[64];
+  LOG(INFO) << "Running debug dump thread.";
+  while (should_run()) {
+    printf("%s", gyro_->GetDebugData().c_str());
+  }
+  LOG(INFO) << "Exiting debug dump thread.";
+}
+
+
+int main(int argc, char ** argv) {
+  int r;
+  google::InitGoogleLogging(argv[0]);
+  google::ParseCommandLineFlags(&argc, &argv, true);
+  google::InstallFailureSignalHandler();
+
+  LibUSB libusb;
+
+  {
+    std::unique_ptr<LibUSBDeviceHandle> dev_handle(
+        CHECK_NOTNULL(libusb.FindDeviceWithVIDPID(FLAGS_vid, FLAGS_pid)));
+
+    GyroDriver gyro(dev_handle.release());
+
+    while(true){
+      	    sleep(50);
+    }
+  }
+  return 0;
+}
diff --git a/gyro_board/src/libusb-driver/get.h b/gyro_board/src/libusb-driver/get.h
new file mode 100644
index 0000000..c0ed6a6
--- /dev/null
+++ b/gyro_board/src/libusb-driver/get.h
@@ -0,0 +1,91 @@
+#ifndef GET_H_
+#define GET_H_
+
+#include <sys/socket.h>
+#include <linux/can.h>
+#include <memory>
+#include <boost/thread/locks.hpp>
+#include <boost/thread.hpp>
+
+#include "thread.h"
+#include "libusb_wrap.h"
+
+// Use a packed version of can_frame.
+// This allows for us to just transfer the data over the wire trivially.
+struct packed_can_frame {
+	canid_t can_id;  /* 32 bit CAN_ID + EFF/RTR/ERR flags */
+	uint8_t can_dlc; /* data length code: 0 .. 8 */
+	uint8_t data[8];
+} __attribute__((packed));
+
+class DbgReader;
+
+// Compare function for CAN IDs.
+struct can_frame_priority_comparator
+    : std::binary_function <struct can_frame,
+                            struct can_frame, bool> {
+  bool operator() (const struct can_frame& x,
+                   const struct can_frame& y) const;
+};
+
+class GyroDriver {
+ public:
+  // Constructs a GyroDriver.
+  // GyroDriver takes ownership of the device handle.
+  explicit GyroDriver(LibUSBDeviceHandle *dev_handle);
+  virtual ~GyroDriver();
+
+  // Queues a CAN frame.  The driver will copy the frame to reduce memory churn
+  // and non-realtime behavior associated with allocating and deallocating the
+  // messages.
+  // Returns true if the message was queued and false otherwise.
+  bool QueueCanFrame(const struct can_frame &msg);
+
+  // Returns 1 packet worth of debug data from the bulk debug channel.
+  std::string GetDebugData();
+
+  // Waits until a CAN frame is available and returns it.
+  // Returns true if we got a frame and false if we were interrupted.
+  bool GetCanFrame(struct can_frame *msg);
+
+  // Terminates the rx and tx threads in preperation for shutdown.
+  // Not safe for use in signal handlers.
+  void Terminate();
+
+ private:
+  // Class that runs in a seperate thread and receives and queues all messages.
+  class PacketReceiver;
+
+  // USB Device handle.
+  std::unique_ptr<LibUSBDeviceHandle> dev_handle_;
+  // Handle for the object run in the debug thread which prints out debug
+  // information.
+  std::unique_ptr<DbgReader> dbg_;
+  // Thread handle for the debug thread.
+  std::unique_ptr<boost::thread> debug_thread_;
+
+  // Handle for the transmit object which runs in the transmit thread and also
+  // handles priority queueing of packets.
+  //std::unique_ptr<PacketTransmitter> tx_;
+  // Thread handle for the transmit thread.
+  //std::unique_ptr<boost::thread> tx_thread_;
+
+  // Handle for the rx object which runs in the rx thread and also
+  // handles priority queueing of packets.
+  std::unique_ptr<PacketReceiver> rx_;
+  // Thread handle for the receive thread.
+  std::unique_ptr<boost::thread> rx_thread_;
+};
+
+class DbgReader : public Thread {
+ public:
+  explicit DbgReader(GyroDriver *dev_handle);
+
+  // Serve.
+  void operator()();
+
+ private:
+  GyroDriver *gyro_;
+};
+
+#endif  // GET_H_
diff --git a/gyro_board/src/libusb-driver/libusb_wrap.cc b/gyro_board/src/libusb-driver/libusb_wrap.cc
new file mode 100644
index 0000000..1f54998
--- /dev/null
+++ b/gyro_board/src/libusb-driver/libusb_wrap.cc
@@ -0,0 +1,101 @@
+#include <libusb.h>
+#include <google/gflags.h>
+#include <glog/logging.h>
+#include <iostream>
+
+#include "libusb_wrap.h"
+
+LibUSB::LibUSB() {
+  CHECK_GE(libusb_init(&ctx_), 0) << ": LibUSB failed to initialize.";
+  libusb_set_debug(ctx_, 3);
+}
+
+LibUSBDeviceHandle *LibUSB::FindDeviceWithVIDPID(int vid, int pid) {
+  int r;
+  libusb_device **devs;
+  libusb_device_handle *dev_handle;
+
+  ssize_t cnt;
+  cnt = libusb_get_device_list(ctx_, &devs);
+  if(cnt < 0) {
+    LOG(ERROR) << "Get Device Error";
+    return NULL;
+  }
+  LOG(INFO) << cnt << " Devices in list.";
+  bool found = false;
+  for (int i = 0; i < cnt; ++i) {
+    struct libusb_device_descriptor desc;
+    r = libusb_get_device_descriptor(devs[i], &desc);
+    CHECK_GE(r, 0) << ": Couldn't get device descriptor, error " << r;
+    if (desc.idVendor == vid && desc.idProduct == pid) {
+      LOG(INFO) << "Device " << (int)libusb_get_bus_number(devs[i]) << ":"
+                << (int)libusb_get_device_address(devs[i]) << " matches";
+      r = libusb_open(devs[i], &dev_handle);
+      if (libusb_kernel_driver_active(dev_handle, 0) == 1) {
+        LOG(INFO) << "Device already in use, trying next one.";
+        continue;
+      }
+      if (r < 0) {
+        LOG(WARNING) << "Failed to open device.";
+      } else {
+        found = true;
+        break;
+      }
+    }
+  }
+  libusb_free_device_list(devs, 1);
+  if (!found) {
+    LOG(ERROR) << "Couldn't open device.";
+    return NULL;
+  }
+
+  if (libusb_kernel_driver_active(dev_handle, 0) == 1) {
+    LOG(INFO) << "Kernel Driver Active";
+    if (libusb_detach_kernel_driver(dev_handle, 0) == 0) {
+      LOG(INFO) << "Kernel Driver Detached!";
+    } else {
+      LOG(ERROR) << "Couldn't detach kernel driver.";
+      return NULL;
+    }
+  }
+
+  r = libusb_claim_interface(dev_handle, 0);
+  if (r < 0) {
+    LOG(ERROR) << "Cannot Claim Interface";
+    return 0;
+  }
+  LOG(INFO) << "Claimed Interface";
+  return new LibUSBDeviceHandle(dev_handle);
+}
+
+LibUSB::~LibUSB() {
+  libusb_exit(ctx_);
+}
+
+LibUSBDeviceHandle::LibUSBDeviceHandle(
+    libusb_device_handle *dev_handle) : dev_handle_(dev_handle) { }
+
+LibUSBDeviceHandle::~LibUSBDeviceHandle() {
+  int r;
+  r = libusb_release_interface(dev_handle_, 0);
+  if (r != 0) {
+    LOG(FATAL) << "Cannot Release Interface";
+  }
+  LOG(INFO) << "Released Interface";
+
+  libusb_close(dev_handle_);
+}
+
+int LibUSBDeviceHandle::interrupt_transfer(
+    unsigned char endpoint, unsigned char *data, int length,
+    int *transferred, unsigned int timeout) {
+  return libusb_interrupt_transfer(dev_handle_, endpoint, data, length,
+                                   transferred, timeout);
+}
+
+int LibUSBDeviceHandle::bulk_transfer(
+    unsigned char endpoint, unsigned char *data,
+    int length, int *transferred, unsigned int timeout) {
+  return libusb_bulk_transfer(dev_handle_, endpoint, data, length,
+                              transferred, timeout);
+}
diff --git a/gyro_board/src/libusb-driver/libusb_wrap.h b/gyro_board/src/libusb-driver/libusb_wrap.h
new file mode 100644
index 0000000..f87f235
--- /dev/null
+++ b/gyro_board/src/libusb-driver/libusb_wrap.h
@@ -0,0 +1,38 @@
+#ifndef LIBUSB_H_
+#define LIBUSB_H_
+
+#include <libusb.h>
+
+class LibUSBDeviceHandle;
+
+class LibUSB {
+ public:
+  explicit LibUSB();
+  virtual ~LibUSB();
+  // Return a device handle or NULL with the correct VID and PID.
+  LibUSBDeviceHandle *FindDeviceWithVIDPID(
+      int vid, int pid);
+
+ private:
+  libusb_context *ctx_;
+};
+
+class LibUSBDeviceHandle {
+ public:
+  virtual ~LibUSBDeviceHandle();
+  // Transfers data using an interrupt transfer.
+  int interrupt_transfer(unsigned char endpoint, unsigned char *data,
+                         int length, int *transferred, unsigned int timeout);
+
+  // Transfers data using a bulk transfer.
+  int bulk_transfer(unsigned char endpoint, unsigned char *data,
+                    int length, int *transferred, unsigned int timeout);
+
+ private:
+  friend class LibUSB; // For constructor
+  // Takes ownership of the device handle and frees it when destructed.
+  explicit LibUSBDeviceHandle(libusb_device_handle *dev_handle);
+ libusb_device_handle *dev_handle_;
+};
+
+#endif  // LIBUSB_H_
diff --git a/gyro_board/src/libusb-driver/signal_handler.cc b/gyro_board/src/libusb-driver/signal_handler.cc
new file mode 100644
index 0000000..ffb1b99
--- /dev/null
+++ b/gyro_board/src/libusb-driver/signal_handler.cc
@@ -0,0 +1,87 @@
+#include "signal_handler.h"
+
+#include <boost/thread/locks.hpp>
+#include <boost/thread.hpp>
+#include <boost/bind.hpp>
+#include <boost/function.hpp>
+#include <google/gflags.h>
+#include <glog/logging.h>
+#include <iostream>
+#include <signal.h>
+#include <stdio.h>
+#include <sys/socket.h>
+#include <linux/can.h>
+#include <memory>
+#include <queue>
+#include <unistd.h>
+
+#include "thread.h"
+
+// Boolean signaling if the handler has been set up or not.
+static bool pipe_has_been_initialized = false;
+
+// Pipe that the signal handler writes the signal number to
+static int handler_write_pipe;
+// Pipe that the handler thread reads the signal number from.
+static int thread_read_pipe;
+// Mutex to lock the signal handler dictionary.
+static boost::mutex signal_dict_lock;
+// Signal handler dictionary.
+static std::unique_ptr<std::map<int, boost::function<void(int)> > > signal_dict;
+
+// Thread which reads signal numbers from the pipe and handles them.
+class SignalHandlerThread: public Thread {
+ public:
+  void operator()() {
+    while (true) {
+      int signal_number;
+      LOG(INFO) << "Back to waiting.";
+      int size = read(thread_read_pipe, &signal_number, sizeof(int));
+      if (size == -1) {
+        continue;
+      }
+      CHECK_EQ(size, sizeof(int))
+          << ": Read the wrong number of bytes when receiving a signal.";
+      LOG(INFO) << "Got signal " << signal_number;
+
+      boost::function<void(int)> function;
+      if (GetFromMap(*signal_dict, signal_number, &function)) {
+        function(signal_number);
+      }
+    }
+  }
+};
+
+static std::unique_ptr<SignalHandlerThread> signal_handler_thread;
+static std::unique_ptr<boost::thread> signal_handler_thread_;
+
+// Simple signal handler which writes the signal number to the pipe.
+static void signal_handler(int signal_number) {
+  CHECK_EQ(write(handler_write_pipe, &signal_number, sizeof(int)),
+           sizeof(int));
+}
+
+void RegisterSignalHandler(int signal_number,
+                           boost::function<void(int)> function){
+  if (!pipe_has_been_initialized) {
+    int pipefd[2];
+    CHECK(!pipe2(pipefd, 0))
+        << ": Failed to create pipes for signal handler.";
+    thread_read_pipe = pipefd[0];
+    handler_write_pipe = pipefd[1];
+    signal_handler_thread.reset(new SignalHandlerThread());
+    signal_handler_thread_.reset(
+        new boost::thread(boost::ref(*signal_handler_thread)));
+    signal_dict.reset(new std::map<int, boost::function<void(int)> >());
+  }
+  struct sigaction new_action, old_action;
+
+  new_action.sa_handler = &signal_handler;
+  sigemptyset(&new_action.sa_mask);
+
+  boost::lock_guard<boost::mutex> lockguard(signal_dict_lock);
+
+  InsertIntoMap(signal_dict.get(), signal_number, function);
+
+  sigaction(signal_number, &new_action, NULL);
+}
diff --git a/gyro_board/src/libusb-driver/signal_handler.h b/gyro_board/src/libusb-driver/signal_handler.h
new file mode 100644
index 0000000..fbc8a37
--- /dev/null
+++ b/gyro_board/src/libusb-driver/signal_handler.h
@@ -0,0 +1,39 @@
+#ifndef SIGNAL_HANDLER_H_
+#define SIGNAL_HANDLER_H_
+
+#include <boost/function.hpp>
+#include <map>
+
+// TODO(aschuh): Template std::map as well.
+// Maps the key to the value, inserting it if it isn't there, or replacing it if
+// it is.  Returns true if the key was added and false if it was replaced.
+template <typename K, typename V>
+bool InsertIntoMap(std::map<K, V> *my_map, const K &key, const V &new_value) {
+  std::pair<typename std::map<K, V>::iterator, bool> element;
+  element = my_map->insert(std::pair<K,V>(key, new_value));
+  if (element.second == false) {
+    element.first->second = new_value;
+  }
+  return element.second;
+}
+
+// Gets the value for the key from the map.
+// Returns true if the key was found and then populates value with the value.
+// Otherwise, leaves value alone and returns false.
+template <typename K, typename V>
+bool GetFromMap(const std::map<K, V> &my_map, const K &key, V *value) {
+  typename std::map<K, V>::const_iterator element = my_map.find(key);
+  if (element != my_map.end()) {
+    *value = element->second;
+    return true;
+  }
+  return false;
+}
+
+
+// Registers a signal handler to be run when we get the specified signal.
+// The handler will run in a thread, rather than in the signal's context.
+void RegisterSignalHandler(int signal_number,
+                           boost::function<void(int)> function);
+
+#endif  // SIGNAL_HANDLER_H_
diff --git a/gyro_board/src/libusb-driver/thread.cc b/gyro_board/src/libusb-driver/thread.cc
new file mode 100644
index 0000000..0121f35
--- /dev/null
+++ b/gyro_board/src/libusb-driver/thread.cc
@@ -0,0 +1,14 @@
+#include "thread.h"
+
+#include <boost/bind.hpp>
+
+
+void Thread::Terminate() {
+  boost::lock_guard<boost::mutex> lockguard(terminate_mutex_);
+  should_terminate_ = true;
+}
+
+bool Thread::should_run() {
+  boost::lock_guard<boost::mutex> lockguard(terminate_mutex_);
+  return !should_terminate_;
+}
diff --git a/gyro_board/src/libusb-driver/thread.h b/gyro_board/src/libusb-driver/thread.h
new file mode 100644
index 0000000..1e94777
--- /dev/null
+++ b/gyro_board/src/libusb-driver/thread.h
@@ -0,0 +1,29 @@
+#ifndef THREAD_H_
+#define THREAD_H_
+
+#include <sys/socket.h>
+#include <linux/can.h>
+#include <boost/thread/locks.hpp>
+#include <boost/thread.hpp>
+
+class Thread {
+ public:
+  // Constructer initializes terminate to false.
+  Thread() : should_terminate_(false) {}
+
+  // Terminate the thread soon.
+  void Terminate();
+
+ protected:
+  // Helper method to atomically read the should_terminate_ boolean.
+  bool should_run();
+
+ private:
+  // Stores whether or not the thread has been asked to quit.
+  // TODO(aschuh): This really should be a Notification...
+  bool should_terminate_;
+  // Mutex to protect should_terminate.
+  boost::mutex terminate_mutex_;
+};
+
+#endif  // THREAD_H_