diff --git a/CMakeLists.txt b/CMakeLists.txt
index 35508e35cdf47d0ef2ac5033a9395f052b984ad2..272973346f6c2c818b207706a430adc510ff7326 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,9 +1,23 @@
+##############################################################################
+# CMake
+##############################################################################
+
 cmake_minimum_required(VERSION 2.8.3)
 project(rosjava_core)
 
-find_package(catkin REQUIRED rosjava_tools)
+##############################################################################
+# Catkin
+##############################################################################
+
+find_package(catkin REQUIRED rosjava_build_tools)
 
-catkin_rosjava_setup()
+catkin_rosjava_setup(uploadArchives)
 
 catkin_package()
 
+##############################################################################
+# Installation
+##############################################################################
+
+install(DIRECTORY ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_MAVEN_DESTINATION}/org/ros/rosjava_core/ 
+        DESTINATION ${CATKIN_GLOBAL_MAVEN_DESTINATION}/org/ros/rosjava_core)
diff --git a/build.gradle b/build.gradle
index 55f85965a5e8a0b3dd69aec0f929f825b132c0a5..90448575930f3d5d47595408a121d4db872bab4f 100644
--- a/build.gradle
+++ b/build.gradle
@@ -14,33 +14,37 @@
  * the License.
  */
 
-task wrapper(type: Wrapper) {
-  gradleVersion = '1.5'
+buildscript {
+    def rosMavenPath = "$System.env.ROS_MAVEN_PATH".split(':').collect { 'file://' + it }
+    repositories {
+        rosMavenPath.each { p ->
+            maven {
+                url p
+            }
+        }
+        mavenLocal()
+        maven {
+            url 'https://github.com/rosjava/rosjava_mvn_repo/raw/master'
+        }
+    }
+    dependencies {
+        classpath group: 'org.ros.rosjava_bootstrap', name: 'gradle_plugins', version: '0.1.+'
+    }
 }
 
+apply plugin: 'catkin'
+
 allprojects {
-  group 'ros.rosjava_core'
-  version = '0.0.0-SNAPSHOT'
+    group 'org.ros.rosjava_core'
+    version = project.catkin.pkg.version
 }
 
 subprojects {
-  if (name != 'docs') {
-    apply plugin: 'java'
-    apply plugin: 'osgi'
-    apply plugin: 'eclipse'
-    apply plugin: 'maven'
-
-    sourceCompatibility = 1.6
-    targetCompatibility = 1.6
-
-    repositories {
-      mavenLocal()
-      maven {
-        url 'https://github.com/rosjava/rosjava_mvn_repo/raw/master'
-      }
+    if (name != 'docs') {
+        apply plugin: 'ros'
+        apply plugin: 'ros-java'
     }
-  }
 }
 
-defaultTasks 'install'
+defaultTasks 'uploadArchives'
 
diff --git a/docs/src/main/sphinx/getting_started.rst b/docs/src/main/sphinx/getting_started.rst
index b1f92176c6f66678fceaac2a13ce15275730d5ed..7d7952c36439ed44ee43b19c03f1c6d63976f23b 100644
--- a/docs/src/main/sphinx/getting_started.rst
+++ b/docs/src/main/sphinx/getting_started.rst
@@ -241,7 +241,7 @@ Services
 The following class (:javadoc:`org.ros.rosjava_tutorial_services.Server`) is
 available from the rosjava_tutorial_services package. In this example, we
 create a :javadoc:`org.ros.node.service.ServiceServer` for the
-``test_ros.AddTwoInts`` service. This should feel relatively familiar if you're
+``rosjava_test_msgs.AddTwoInts`` service. This should feel relatively familiar if you're
 a ROS veteran.
 
 .. literalinclude:: ../../../../rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
diff --git a/rosjava_bootstrap/build.gradle b/message_generation_tests/build.gradle
similarity index 60%
rename from rosjava_bootstrap/build.gradle
rename to message_generation_tests/build.gradle
index 804459d21894dbbaa5f67d53f99d95bf4976d5d7..b0fc72bdbc3cc8beacdd3724f5b6e1501cf69110 100644
--- a/rosjava_bootstrap/build.gradle
+++ b/message_generation_tests/build.gradle
@@ -15,19 +15,23 @@
  */
 
 dependencies {
-  compile 'org.apache.commons:com.springsource.org.apache.commons.codec:1.3.0'
-  compile 'org.apache.commons:com.springsource.org.apache.commons.lang:2.4.0'
-  compile 'org.apache.commons:com.springsource.org.apache.commons.io:1.4.0'
-  compile 'commons-pool:commons-pool:1.6'
-  compile 'com.google.guava:guava:12.0'
-  compile 'io.netty:netty:3.5.2.Final'
+  compile 'org.ros.rosjava_messages:rosjava_test_msgs:0.1.+'
+  compile 'org.ros.rosjava_bootstrap:message_generation:0.1.+'
   testCompile 'junit:junit:4.8.2'
 }
-
 jar {
   manifest {
-    version = '0.0.0-SNAPSHOT'
-    symbolicName = 'org.ros.rosjava_bootstrap'
+    version = project.version
+    symbolicName = 'org.ros.rosjava_core.message_generation_tests'
   }
 }
 
+/* 
+ * Ugly hack to stop osgi/java plugin combination from barfing
+ * when there are no sources. 
+ */
+task bugfixtask << {
+    mkdir sourceSets.main.output.classesDir
+}
+
+jar.dependsOn(bugfixtask)
diff --git a/rosjava_bootstrap/src/test/java/org/ros/internal/message/Md5GeneratorTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/Md5GeneratorTest.java
similarity index 89%
rename from rosjava_bootstrap/src/test/java/org/ros/internal/message/Md5GeneratorTest.java
rename to message_generation_tests/src/test/java/org/ros/internal/message/Md5GeneratorTest.java
index 45a68724944688f76d095c05d9ed29c2f78832ed..6746f86b59aa2d24fb765a33ef456619840f05ca 100644
--- a/rosjava_bootstrap/src/test/java/org/ros/internal/message/Md5GeneratorTest.java
+++ b/message_generation_tests/src/test/java/org/ros/internal/message/Md5GeneratorTest.java
@@ -52,31 +52,31 @@ public class Md5GeneratorTest {
   @Test
   public void testPrimitives() {
     TopicDescription topicDescription =
-        topicDescriptionFactory.newFromType("test_ros/TestPrimitives");
+        topicDescriptionFactory.newFromType("rosjava_test_msgs/TestPrimitives");
     assertEquals("3e70f428a22c0d26ca67f87802c8e00f", topicDescription.getMd5Checksum());
   }
 
   @Test
   public void testString() {
-    TopicDescription topicDescription = topicDescriptionFactory.newFromType("test_ros/TestString");
+    TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/TestString");
     assertEquals("334ff4377be93faa44ebc66d23d40fd3", topicDescription.getMd5Checksum());
   }
 
   @Test
   public void testHeader() {
-    TopicDescription topicDescription = topicDescriptionFactory.newFromType("test_ros/TestHeader");
+    TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/TestHeader");
     assertEquals("4b5a00f536da2f756ba6aebcf795a967", topicDescription.getMd5Checksum());
   }
 
   @Test
   public void testArrays() {
-    TopicDescription topicDescription = topicDescriptionFactory.newFromType("test_ros/TestArrays");
+    TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/TestArrays");
     assertEquals("4cc9b5e2cebe791aa3e994f5bc159eb6", topicDescription.getMd5Checksum());
   }
 
   @Test
   public void testComposite() {
-    TopicDescription topicDescription = topicDescriptionFactory.newFromType("test_ros/Composite");
+    TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/Composite");
     assertEquals("d8fb6eb869ad3956b50e8737d96dc9fa", topicDescription.getMd5Checksum());
   }
 
@@ -95,14 +95,14 @@ public class Md5GeneratorTest {
   @Test
   public void testAddTwoInts() {
     ServiceDescription serviceDescription =
-        serviceDescriptionFactory.newFromType("test_ros/AddTwoInts");
+        serviceDescriptionFactory.newFromType("rosjava_test_msgs/AddTwoInts");
     assertEquals("6a2e34150c00229791cc89ff309fff21", serviceDescription.getMd5Checksum());
   }
 
   @Test
   public void testTransitiveSrv() {
     ServiceDescription serviceDescription =
-        serviceDescriptionFactory.newFromType("test_rospy/TransitiveSrv");
+        serviceDescriptionFactory.newFromType("rosjava_test_msgspy/TransitiveSrv");
     assertEquals("8b7918ee2b81eaf825f4c70de011f6fa", serviceDescription.getMd5Checksum());
   }
 }
diff --git a/rosjava_bootstrap/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java
rename to message_generation_tests/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java
diff --git a/rosjava_bootstrap/src/test/java/org/ros/internal/message/MessageTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/MessageTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/internal/message/MessageTest.java
rename to message_generation_tests/src/test/java/org/ros/internal/message/MessageTest.java
diff --git a/rosjava_bootstrap/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java
rename to message_generation_tests/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java
diff --git a/rosjava_bootstrap/src/test/java/org/ros/internal/message/ServiceTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/ServiceTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/internal/message/ServiceTest.java
rename to message_generation_tests/src/test/java/org/ros/internal/message/ServiceTest.java
diff --git a/rosjava_bootstrap/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java
rename to message_generation_tests/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java
diff --git a/rosjava_bootstrap/src/test/java/org/ros/message/DurationTest.java b/message_generation_tests/src/test/java/org/ros/message/DurationTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/message/DurationTest.java
rename to message_generation_tests/src/test/java/org/ros/message/DurationTest.java
diff --git a/rosjava_bootstrap/src/test/java/org/ros/message/TimeTest.java b/message_generation_tests/src/test/java/org/ros/message/TimeTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/message/TimeTest.java
rename to message_generation_tests/src/test/java/org/ros/message/TimeTest.java
diff --git a/package.xml b/package.xml
index 60c68d151337ba599c15b0cdb027b3b93920bff5..7b340fad272256fe082aaf72f36bbffe5f3de5b0 100644
--- a/package.xml
+++ b/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package>
   <name>rosjava_core</name>
-  <version>0.0.0</version>
+  <version>0.1.0</version>
   <description>
     An implementation of ROS in pure-Java with Android support.
   </description>
@@ -10,6 +10,8 @@
   <license>Apache 2.0</license>
 
   <buildtool_depend>catkin</buildtool_depend>
-  <build_depend>rosjava_tools</build_depend>
+  <build_depend>rosjava_build_tools</build_depend>
+  <build_depend>rosjava_bootstrap</build_depend>
+  <build_depend>rosjava_messages</build_depend>
 </package>
 
diff --git a/rosdep.yaml b/rosdep.yaml
deleted file mode 100644
index 7120d3816c681665b5964d47b76291e3716bc156..0000000000000000000000000000000000000000
--- a/rosdep.yaml
+++ /dev/null
@@ -1,13 +0,0 @@
-java:
-  ubuntu: openjdk-6-jdk
-  debian: openjdk-6-jdk
-  arch: openjdk6
-  macports: |
-  gentoo: dev-java/sun-jdk
-  freebsd: openjdk6
-ant:
-  ubuntu: 
-    lucid: ant1.8
-    maverick: ant
-    natty: ant
-    oneiric: ant
diff --git a/rosjava/build.gradle b/rosjava/build.gradle
index 5afcdbb5b0d531b9a968705b0f9bfd8c763a5396..b2b44a132b527a5038414812581407f85b42ff66 100644
--- a/rosjava/build.gradle
+++ b/rosjava/build.gradle
@@ -15,21 +15,26 @@
  */
 
 dependencies {
-  compile project(':rosjava_bootstrap')
-  compile project(':rosjava_messages')
   compile project(':apache_xmlrpc_common')
   compile project(':apache_xmlrpc_server')
   compile project(':apache_xmlrpc_client')
+  compile 'org.ros.rosjava_bootstrap:message_generation:0.1.+'
+  compile 'org.ros.rosjava_messages:rosjava_test_msgs:0.1.+'
+  compile 'org.ros.rosjava_messages:rosgraph_msgs:1.9.+'
+  compile 'org.ros.rosjava_messages:geometry_msgs:1.10.+'
+  compile 'org.ros.rosjava_messages:nav_msgs:1.10.+'
+  compile 'org.ros.rosjava_messages:tf2_msgs:0.4.+'
   compile 'dnsjava:dnsjava:2.1.1'
   compile 'org.apache.commons:com.springsource.org.apache.commons.logging:1.1.1'
   compile 'org.apache.commons:com.springsource.org.apache.commons.net:2.0.0'
+  compile 'com.google.guava:guava:12.0'
   testCompile 'junit:junit:4.8.2'
   testCompile 'org.mockito:mockito-all:1.8.5'
 }
 
 jar {
   manifest {
-    version = '0.0.0-SNAPSHOT'
+    version = project.version
     symbolicName = 'org.ros.rosjava'
     instruction 'Export-Package', '!org.ros.internal.*, org.ros.*'
     instruction 'Private-Package', 'org.ros.internal.*'
diff --git a/rosjava_bootstrap/src/main/java/org/ros/CommandLineVariables.java b/rosjava/src/main/java/org/ros/CommandLineVariables.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/CommandLineVariables.java
rename to rosjava/src/main/java/org/ros/CommandLineVariables.java
diff --git a/rosjava_bootstrap/src/main/java/org/ros/EnvironmentVariables.java b/rosjava/src/main/java/org/ros/EnvironmentVariables.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/EnvironmentVariables.java
rename to rosjava/src/main/java/org/ros/EnvironmentVariables.java
diff --git a/rosjava_bootstrap/src/main/java/org/ros/Parameters.java b/rosjava/src/main/java/org/ros/Parameters.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/Parameters.java
rename to rosjava/src/main/java/org/ros/Parameters.java
diff --git a/rosjava_bootstrap/src/main/java/org/ros/Topics.java b/rosjava/src/main/java/org/ros/Topics.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/Topics.java
rename to rosjava/src/main/java/org/ros/Topics.java
diff --git a/rosjava_bootstrap/src/main/java/org/ros/exception/RosException.java b/rosjava/src/main/java/org/ros/exception/RosException.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/exception/RosException.java
rename to rosjava/src/main/java/org/ros/exception/RosException.java
diff --git a/rosjava_bootstrap/src/main/java/org/ros/exception/RosRuntimeException.java b/rosjava/src/main/java/org/ros/exception/RosRuntimeException.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/exception/RosRuntimeException.java
rename to rosjava/src/main/java/org/ros/exception/RosRuntimeException.java
diff --git a/rosjava_bootstrap/src/main/java/org/ros/namespace/GraphName.java b/rosjava/src/main/java/org/ros/namespace/GraphName.java
similarity index 100%
rename from rosjava_bootstrap/src/main/java/org/ros/namespace/GraphName.java
rename to rosjava/src/main/java/org/ros/namespace/GraphName.java
diff --git a/rosjava/src/main/java/org/ros/node/ConnectedNode.java b/rosjava/src/main/java/org/ros/node/ConnectedNode.java
index ea9753d1871cc0d31a95815f609b62198c327aa4..34d6994c1edbf6d682353b574272d806d776e955 100644
--- a/rosjava/src/main/java/org/ros/node/ConnectedNode.java
+++ b/rosjava/src/main/java/org/ros/node/ConnectedNode.java
@@ -93,7 +93,7 @@ public interface ConnectedNode extends Node {
    * @param serviceName
    *          the name of the service
    * @param serviceType
-   *          the type of the service (e.g. "test_ros/AddTwoInts")
+   *          the type of the service (e.g. "rosjava_test_msgs/AddTwoInts")
    * @param serviceResponseBuilder
    *          called for every request to build a response
    * @return a {@link ServiceServer}
@@ -139,7 +139,7 @@ public interface ConnectedNode extends Node {
    * @param serviceName
    *          the name of the service
    * @param serviceType
-   *          the type of the service (e.g. "test_ros/AddTwoInts")
+   *          the type of the service (e.g. "rosjava_test_msgs/AddTwoInts")
    * @return a {@link ServiceClient}
    * @throws ServiceNotFoundException
    *           thrown if no matching service could be found
diff --git a/rosjava_bootstrap/src/test/java/org/ros/namespace/GraphNameTest.java b/rosjava/src/test/java/org/ros/namespace/GraphNameTest.java
similarity index 100%
rename from rosjava_bootstrap/src/test/java/org/ros/namespace/GraphNameTest.java
rename to rosjava/src/test/java/org/ros/namespace/GraphNameTest.java
diff --git a/rosjava/src/test/java/org/ros/node/service/ServiceIntegrationTest.java b/rosjava/src/test/java/org/ros/node/service/ServiceIntegrationTest.java
index a338ff5337fe09d90dc5171ac6f252297c1f2062..edba59334cc6e721fdb4727a1728a963f6e90879 100644
--- a/rosjava/src/test/java/org/ros/node/service/ServiceIntegrationTest.java
+++ b/rosjava/src/test/java/org/ros/node/service/ServiceIntegrationTest.java
@@ -43,7 +43,7 @@ public class ServiceIntegrationTest extends RosTest {
 
   @Test
   public void testPesistentServiceConnection() throws Exception {
-    final CountDownServiceServerListener<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> countDownServiceServerListener =
+    final CountDownServiceServerListener<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> countDownServiceServerListener =
         CountDownServiceServerListener.newDefault();
     nodeMainExecutor.execute(new AbstractNodeMain() {
       @Override
@@ -53,20 +53,20 @@ public class ServiceIntegrationTest extends RosTest {
 
       @Override
       public void onStart(final ConnectedNode connectedNode) {
-        ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer =
+        ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
             connectedNode
                 .newServiceServer(
                     SERVICE_NAME,
-                    test_ros.AddTwoInts._TYPE,
-                    new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
+                    rosjava_test_msgs.AddTwoInts._TYPE,
+                    new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
                       @Override
-                      public void build(test_ros.AddTwoIntsRequest request,
-                          test_ros.AddTwoIntsResponse response) {
+                      public void build(rosjava_test_msgs.AddTwoIntsRequest request,
+                          rosjava_test_msgs.AddTwoIntsResponse response) {
                         response.setSum(request.getA() + request.getB());
                       }
                     });
         try {
-          connectedNode.newServiceServer(SERVICE_NAME, test_ros.AddTwoInts._TYPE, null);
+          connectedNode.newServiceServer(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE, null);
           fail();
         } catch (DuplicateServiceException e) {
           // Only one ServiceServer with a given name can be created.
@@ -86,23 +86,23 @@ public class ServiceIntegrationTest extends RosTest {
 
       @Override
       public void onStart(ConnectedNode connectedNode) {
-        ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
+        ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
         try {
-          serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
+          serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
           // Test that requesting another client for the same service returns
           // the same instance.
           ServiceClient<?, ?> duplicate =
-              connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
+              connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
           assertEquals(serviceClient, duplicate);
         } catch (ServiceNotFoundException e) {
           throw new RosRuntimeException(e);
         }
-        test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
+        rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
         request.setA(2);
         request.setB(2);
-        serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
+        serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
           @Override
-          public void onSuccess(test_ros.AddTwoIntsResponse response) {
+          public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
             assertEquals(response.getSum(), 4);
             latch.countDown();
           }
@@ -116,9 +116,9 @@ public class ServiceIntegrationTest extends RosTest {
         // Regression test for issue 122.
         request.setA(3);
         request.setB(3);
-        serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
+        serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
           @Override
-          public void onSuccess(test_ros.AddTwoIntsResponse response) {
+          public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
             assertEquals(response.getSum(), 6);
             latch.countDown();
           }
@@ -137,7 +137,7 @@ public class ServiceIntegrationTest extends RosTest {
   @Test
   public void testRequestFailure() throws Exception {
     final String errorMessage = "Error!";
-    final CountDownServiceServerListener<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> countDownServiceServerListener =
+    final CountDownServiceServerListener<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> countDownServiceServerListener =
         CountDownServiceServerListener.newDefault();
     nodeMainExecutor.execute(new AbstractNodeMain() {
       @Override
@@ -147,15 +147,15 @@ public class ServiceIntegrationTest extends RosTest {
 
       @Override
       public void onStart(ConnectedNode connectedNode) {
-        ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer =
+        ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
             connectedNode
                 .newServiceServer(
                     SERVICE_NAME,
-                    test_ros.AddTwoInts._TYPE,
-                    new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
+                    rosjava_test_msgs.AddTwoInts._TYPE,
+                    new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
                       @Override
-                      public void build(test_ros.AddTwoIntsRequest request,
-                          test_ros.AddTwoIntsResponse response) throws ServiceException {
+                      public void build(rosjava_test_msgs.AddTwoIntsRequest request,
+                          rosjava_test_msgs.AddTwoIntsResponse response) throws ServiceException {
                         throw new ServiceException(errorMessage);
                       }
                     });
@@ -174,16 +174,16 @@ public class ServiceIntegrationTest extends RosTest {
 
       @Override
       public void onStart(ConnectedNode connectedNode) {
-        ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
+        ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
         try {
-          serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
+          serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
         } catch (ServiceNotFoundException e) {
           throw new RosRuntimeException(e);
         }
-        test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
-        serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
+        rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
+        serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
           @Override
-          public void onSuccess(test_ros.AddTwoIntsResponse message) {
+          public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse message) {
             fail();
           }
 
diff --git a/rosjava/src/test/java/org/ros/node/topic/TopicIntegrationTest.java b/rosjava/src/test/java/org/ros/node/topic/TopicIntegrationTest.java
index 2c2f591997214bb2f3a20d1fa5a8efc7d24f84d5..d6aa4e5994749c1f7e99e8e441f4e940f24e4453 100644
--- a/rosjava/src/test/java/org/ros/node/topic/TopicIntegrationTest.java
+++ b/rosjava/src/test/java/org/ros/node/topic/TopicIntegrationTest.java
@@ -175,13 +175,13 @@ public class TopicIntegrationTest extends RosTest {
     }, nodeConfiguration);
   }
 
-  private final class Listener implements MessageListener<test_ros.TestHeader> {
+  private final class Listener implements MessageListener<rosjava_test_msgs.TestHeader> {
     private final CountDownLatch latch = new CountDownLatch(10);
 
-    private test_ros.TestHeader lastMessage;
+    private rosjava_test_msgs.TestHeader lastMessage;
 
     @Override
-    public void onNewMessage(test_ros.TestHeader message) {
+    public void onNewMessage(rosjava_test_msgs.TestHeader message) {
       int seq = message.getHeader().getSeq();
       long stamp = message.getHeader().getStamp().totalNsecs();
       if (lastMessage != null) {
@@ -210,13 +210,13 @@ public class TopicIntegrationTest extends RosTest {
 
       @Override
       public void onStart(final ConnectedNode connectedNode) {
-        final Publisher<test_ros.TestHeader> publisher =
-            connectedNode.newPublisher("foo", test_ros.TestHeader._TYPE);
+        final Publisher<rosjava_test_msgs.TestHeader> publisher =
+            connectedNode.newPublisher("foo", rosjava_test_msgs.TestHeader._TYPE);
         connectedNode.executeCancellableLoop(new CancellableLoop() {
           @Override
           public void loop() throws InterruptedException {
-            test_ros.TestHeader message =
-                connectedNode.getTopicMessageFactory().newFromType(test_ros.TestHeader._TYPE);
+            rosjava_test_msgs.TestHeader message =
+                connectedNode.getTopicMessageFactory().newFromType(rosjava_test_msgs.TestHeader._TYPE);
             message.getHeader().setStamp(connectedNode.getCurrentTime());
             publisher.publish(message);
             // There needs to be some time between messages in order to
@@ -236,8 +236,8 @@ public class TopicIntegrationTest extends RosTest {
 
       @Override
       public void onStart(ConnectedNode connectedNode) {
-        Subscriber<test_ros.TestHeader> subscriber =
-            connectedNode.newSubscriber("foo", test_ros.TestHeader._TYPE);
+        Subscriber<rosjava_test_msgs.TestHeader> subscriber =
+            connectedNode.newSubscriber("foo", rosjava_test_msgs.TestHeader._TYPE);
         subscriber.addMessageListener(listener, QUEUE_CAPACITY);
       }
     }, nodeConfiguration);
diff --git a/rosjava/test/composite_publisher.py b/rosjava/test/composite_publisher.py
index 313a66ed0e8ff43980f8d32354aa119837379f7a..54626ca1374c84de02cc274d309021d7e3a3a9b5 100755
--- a/rosjava/test/composite_publisher.py
+++ b/rosjava/test/composite_publisher.py
@@ -1,14 +1,14 @@
 #!/usr/bin/env python
 from ros import rospy
-from ros import test_ros
-import test_ros.msg
+from ros import rosjava_test_msgs
+import rosjava_test_msgs.msg
 import random
 
 def publisher():
   rospy.init_node('composite_publisher')
-  pub = rospy.Publisher('composite_in', test_ros.msg.Composite)
+  pub = rospy.Publisher('composite_in', rosjava_test_msgs.msg.Composite)
   r = rospy.Rate(10)
-  m = test_ros.msg.Composite()
+  m = rosjava_test_msgs.msg.Composite()
   m.a.x = random.random() * 10000.
   m.a.y = random.random() * 10000.
   m.a.z = random.random() * 10000.
diff --git a/rosjava/test/test_composite_passthrough.py b/rosjava/test/test_composite_passthrough.py
index 5014b0c86840dce7223205fdb1f3efeaf5fada79..53ea068ac4addb7ef75db4eeb4b9f67b98cefcb4 100755
--- a/rosjava/test/test_composite_passthrough.py
+++ b/rosjava/test/test_composite_passthrough.py
@@ -38,14 +38,14 @@ NAME = 'composite_passthrough'
 import roslib; roslib.load_manifest(PKG)
 
 from ros import rospy
-from ros import test_ros
+from ros import rosjava_test_msgs
 from ros import rostest
 
 import sys
 import time
 import unittest
 
-from test_ros.msg import Composite
+from rosjava_test_msgs.msg import Composite
 
 class CompositePassthrough(unittest.TestCase):
         
diff --git a/rosjava/test/test_parameter_client.py b/rosjava/test/test_parameter_client.py
index 7701f5e3c460827131789792aa7a9a1b26e1cc63..85ee40613ef631fc4673dfee1c434e2abdd87f79 100755
--- a/rosjava/test/test_parameter_client.py
+++ b/rosjava/test/test_parameter_client.py
@@ -48,7 +48,7 @@ import time
 import unittest
 
 from std_msgs.msg import String, Bool, Int64, Float64
-from test_ros.msg import Composite, CompositeA, CompositeB, TestArrays
+from rosjava_test_msgs.msg import Composite, CompositeA, CompositeB, TestArrays
 
 class TestParameterClient(unittest.TestCase):
         
diff --git a/rosjava/test/test_testheader_passthrough.py b/rosjava/test/test_testheader_passthrough.py
index 29746b11812296707aef1819899f90d1147d042b..b6ca6a8bb2cc6d28e44b3329fd0dff7e36e8d687 100755
--- a/rosjava/test/test_testheader_passthrough.py
+++ b/rosjava/test/test_testheader_passthrough.py
@@ -38,14 +38,14 @@ NAME = 'testheader_passthrough'
 import roslib; roslib.load_manifest(PKG)
 
 from ros import rospy
-from ros import test_ros
+from ros import rosjava_test_msgs
 from ros import rostest
 
 import sys
 import time
 import unittest
 
-from test_ros.msg import TestHeader
+from rosjava_test_msgs.msg import TestHeader
 
 class TestHeaderPassthrough(unittest.TestCase):
         
diff --git a/rosjava/test/testheader_publisher.py b/rosjava/test/testheader_publisher.py
index 912d838111685ab4c714b5a4c948a5c04da4b685..276334af822fc556e908d615f0790af70bfc7faa 100755
--- a/rosjava/test/testheader_publisher.py
+++ b/rosjava/test/testheader_publisher.py
@@ -1,13 +1,13 @@
 #!/usr/bin/env python
 from ros import rospy
-from ros import test_ros
-import test_ros.msg
+from ros import rosjava_test_msgs
+import rosjava_test_msgs.msg
 
 def publisher():
   rospy.init_node('testheader_publisher')
-  pub = rospy.Publisher('test_header_in', test_ros.msg.TestHeader)
+  pub = rospy.Publisher('test_header_in', rosjava_test_msgs.msg.TestHeader)
   r = rospy.Rate(10)
-  m = test_ros.msg.TestHeader()
+  m = rosjava_test_msgs.msg.TestHeader()
   m.caller_id = rospy.get_name()
   m.header.stamp = rospy.get_rostime()
   while not rospy.is_shutdown():
diff --git a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/cache.properties b/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/cache.properties
deleted file mode 100644
index 43b13728c23a72cc10a1b94319131aad0d85f970..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/cache.properties
+++ /dev/null
@@ -1 +0,0 @@
-#Tue Feb 28 09:35:28 CET 2012
diff --git a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/cache.properties.lock b/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/cache.properties.lock
deleted file mode 100644
index 40fdece9d24d300eb3ed6177f4a7a7952db584cd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/cache.properties.lock
+++ /dev/null
@@ -1 +0,0 @@
-
\ No newline at end of file
diff --git a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/fileHashes.bin b/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/fileHashes.bin
deleted file mode 100644
index 1994afe634093031c7eee19d5ae56e50ca79e98d..0000000000000000000000000000000000000000
Binary files a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/fileHashes.bin and /dev/null differ
diff --git a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/fileSnapshots.bin b/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/fileSnapshots.bin
deleted file mode 100644
index d34d774e01d0e8476255bb899da007becd88a639..0000000000000000000000000000000000000000
Binary files a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/fileSnapshots.bin and /dev/null differ
diff --git a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/outputFileStates.bin b/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/outputFileStates.bin
deleted file mode 100644
index 2a9b50a5d93b31a99e11c241f1288227368843e6..0000000000000000000000000000000000000000
Binary files a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/outputFileStates.bin and /dev/null differ
diff --git a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/taskArtifacts.bin b/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/taskArtifacts.bin
deleted file mode 100644
index a085d070669f9f4f7764e101f259919305a7a8b3..0000000000000000000000000000000000000000
Binary files a/rosjava_bootstrap/.gradle/1.0-milestone-8a/taskArtifacts/taskArtifacts.bin and /dev/null differ
diff --git a/rosjava_bootstrap/.pydevproject b/rosjava_bootstrap/.pydevproject
deleted file mode 100644
index bfca96d8b1348c485e11782e6ed5484de9ec8394..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/.pydevproject
+++ /dev/null
@@ -1,10 +0,0 @@
-<?xml version="1.0" encoding="UTF-8" standalone="no"?>
-<?eclipse-pydev version="1.0"?>
-
-<pydev_project>
-<pydev_property name="org.python.pydev.PYTHON_PROJECT_INTERPRETER">Default</pydev_property>
-<pydev_property name="org.python.pydev.PYTHON_PROJECT_VERSION">python 2.7</pydev_property>
-<pydev_pathproperty name="org.python.pydev.PROJECT_SOURCE_PATH">
-<path>/rosjava_bootstrap/src/main/python</path>
-</pydev_pathproperty>
-</pydev_project>
diff --git a/rosjava_bootstrap/src/main/java/org/ros/exception/package-info.java b/rosjava_bootstrap/src/main/java/org/ros/exception/package-info.java
deleted file mode 100644
index 895f12d64b4a735ce0f1408acd94f5f2876c0e88..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/exception/package-info.java
+++ /dev/null
@@ -1,20 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-/**
- * Provides the classes for representing common rosjava exceptions.
- */
-package org.ros.exception;
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageDeserializer.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageDeserializer.java
deleted file mode 100644
index 507f1c9b8667f318b7bdf378fa267fbba3e50f89..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageDeserializer.java
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.internal.message.field.Field;
-import org.ros.message.MessageDeserializer;
-import org.ros.message.MessageFactory;
-import org.ros.message.MessageIdentifier;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class DefaultMessageDeserializer<T> implements MessageDeserializer<T> {
-
-  private final MessageIdentifier messageIdentifier;
-  private final MessageFactory messageFactory;
-
-  public DefaultMessageDeserializer(MessageIdentifier messageIdentifier,
-      MessageFactory messageFactory) {
-    this.messageIdentifier = messageIdentifier;
-    this.messageFactory = messageFactory;
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public T deserialize(ChannelBuffer buffer) {
-    Message message = messageFactory.newFromType(messageIdentifier.getType());
-    for (Field field : message.toRawMessage().getFields()) {
-      if (!field.isConstant()) {
-        field.deserialize(buffer);
-      }
-    }
-    return (T) message;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageFactory.java
deleted file mode 100644
index 97d817ea6de108b94e76d9ffc4e527f7024a1623..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageFactory.java
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.annotations.VisibleForTesting;
-
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageFactory;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class DefaultMessageFactory implements MessageFactory {
-
-  private final MessageDefinitionProvider messageDefinitionProvider;
-  private final DefaultMessageInterfaceClassProvider messageInterfaceClassProvider;
-  private final MessageProxyFactory messageProxyFactory;
-
-  public DefaultMessageFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    this.messageDefinitionProvider = messageDefinitionProvider;
-    messageInterfaceClassProvider = new DefaultMessageInterfaceClassProvider();
-    messageProxyFactory = new MessageProxyFactory(getMessageInterfaceClassProvider(), this);
-  }
-
-  @Override
-  public <T> T newFromType(String messageType) {
-    String messageDefinition = messageDefinitionProvider.get(messageType);
-    MessageDeclaration messageDeclaration = MessageDeclaration.of(messageType, messageDefinition);
-    return messageProxyFactory.newMessageProxy(messageDeclaration);
-  }
-
-  @VisibleForTesting
-  DefaultMessageInterfaceClassProvider getMessageInterfaceClassProvider() {
-    return messageInterfaceClassProvider;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageInterfaceClassProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageInterfaceClassProvider.java
deleted file mode 100644
index 8de583d0122031956ad580f8823a251f317ccc95..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageInterfaceClassProvider.java
+++ /dev/null
@@ -1,55 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.annotations.VisibleForTesting;
-import com.google.common.collect.Maps;
-
-import java.util.Map;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class DefaultMessageInterfaceClassProvider implements MessageInterfaceClassProvider {
-
-  private final Map<String, Class<?>> cache;
-
-  public DefaultMessageInterfaceClassProvider() {
-    cache = Maps.newConcurrentMap();
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public <T> Class<T> get(String messageType) {
-    if (cache.containsKey(messageType)) {
-      return (Class<T>) cache.get(messageType);
-    }
-    try {
-      String className = messageType.replace("/", ".");
-      Class<T> messageInterfaceClass = (Class<T>) getClass().getClassLoader().loadClass(className);
-      cache.put(messageType, messageInterfaceClass);
-      return messageInterfaceClass;
-    } catch (ClassNotFoundException e) {
-      return (Class<T>) RawMessage.class;
-    }
-  }
-
-  @VisibleForTesting
-  <T> void add(String messageType, Class<T> messageInterfaceClass) {
-    cache.put(messageType, messageInterfaceClass);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageSerializationFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageSerializationFactory.java
deleted file mode 100644
index 726b5d842ef73955a83d0ab664ad7d97d11c8b02..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageSerializationFactory.java
+++ /dev/null
@@ -1,80 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.ros.internal.message.service.ServiceRequestMessageFactory;
-import org.ros.internal.message.service.ServiceResponseMessageFactory;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageDeserializer;
-import org.ros.message.MessageFactory;
-import org.ros.message.MessageIdentifier;
-import org.ros.message.MessageSerializationFactory;
-import org.ros.message.MessageSerializer;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class DefaultMessageSerializationFactory implements MessageSerializationFactory {
-
-  private final MessageFactory topicMessageFactory;
-  private final ServiceRequestMessageFactory serviceRequestMessageFactory;
-  private final ServiceResponseMessageFactory serviceResponseMessageFactory;
-
-  public DefaultMessageSerializationFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    topicMessageFactory = new DefaultMessageFactory(messageDefinitionProvider);
-    serviceRequestMessageFactory = new ServiceRequestMessageFactory(messageDefinitionProvider);
-    serviceResponseMessageFactory = new ServiceResponseMessageFactory(messageDefinitionProvider);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public <T> MessageSerializer<T> newMessageSerializer(String messageType) {
-    return (MessageSerializer<T>) new DefaultMessageSerializer();
-  }
-
-  @Override
-  public <T> MessageDeserializer<T> newMessageDeserializer(String messageType) {
-    return new DefaultMessageDeserializer<T>(MessageIdentifier.of(messageType),
-        topicMessageFactory);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public <T> MessageSerializer<T> newServiceRequestSerializer(String serviceType) {
-    return (MessageSerializer<T>) new DefaultMessageSerializer();
-  }
-
-  @Override
-  public <T> org.ros.message.MessageDeserializer<T>
-      newServiceRequestDeserializer(String serviceType) {
-    return new DefaultMessageDeserializer<T>(MessageIdentifier.of(serviceType),
-        serviceRequestMessageFactory);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public <T> org.ros.message.MessageSerializer<T> newServiceResponseSerializer(String serviceType) {
-    return (MessageSerializer<T>) new DefaultMessageSerializer();
-  }
-
-  @Override
-  public <T> org.ros.message.MessageDeserializer<T> newServiceResponseDeserializer(
-      String serviceType) {
-    return new DefaultMessageDeserializer<T>(MessageIdentifier.of(serviceType),
-        serviceResponseMessageFactory);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageSerializer.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageSerializer.java
deleted file mode 100644
index a71a597c73a03fcb42de5bae2f626aaff786cc44..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/DefaultMessageSerializer.java
+++ /dev/null
@@ -1,36 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.internal.message.field.Field;
-import org.ros.message.MessageSerializer;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class DefaultMessageSerializer implements MessageSerializer<Message> {
-
-  @Override
-  public void serialize(Message message, ChannelBuffer buffer) {
-    for (Field field : message.toRawMessage().getFields()) {
-      if (!field.isConstant()) {
-        field.serialize(buffer);
-      }
-    }
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/GenerateInterfaces.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/GenerateInterfaces.java
deleted file mode 100644
index 039f5e73cac97e42a8f3a5dffac1747273717d4c..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/GenerateInterfaces.java
+++ /dev/null
@@ -1,172 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.collect.Lists;
-import com.google.common.collect.Sets;
-
-import org.apache.commons.io.FileUtils;
-import org.ros.EnvironmentVariables;
-import org.ros.exception.RosRuntimeException;
-import org.ros.internal.message.definition.MessageDefinitionProviderChain;
-import org.ros.internal.message.definition.MessageDefinitionTupleParser;
-import org.ros.internal.message.service.ServiceDefinitionFileProvider;
-import org.ros.internal.message.topic.TopicDefinitionFileProvider;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageFactory;
-import org.ros.message.MessageIdentifier;
-
-import java.io.File;
-import java.io.IOException;
-import java.util.Collection;
-import java.util.List;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class GenerateInterfaces {
-
-  private final TopicDefinitionFileProvider topicDefinitionFileProvider;
-  private final ServiceDefinitionFileProvider serviceDefinitionFileProvider;
-  private final MessageDefinitionProviderChain messageDefinitionProviderChain;
-  private final MessageFactory messageFactory;
-
-  public GenerateInterfaces() {
-    messageDefinitionProviderChain = new MessageDefinitionProviderChain();
-    topicDefinitionFileProvider = new TopicDefinitionFileProvider();
-    messageDefinitionProviderChain.addMessageDefinitionProvider(topicDefinitionFileProvider);
-    serviceDefinitionFileProvider = new ServiceDefinitionFileProvider();
-    messageDefinitionProviderChain.addMessageDefinitionProvider(serviceDefinitionFileProvider);
-    messageFactory = new DefaultMessageFactory(messageDefinitionProviderChain);
-  }
-
-  /**
-   * @param packages
-   *          a list of packages containing the topic types to generate
-   *          interfaces for
-   * @param outputDirectory
-   *          the directory to write the generated interfaces to
-   * @throws IOException
-   */
-  private void writeTopicInterfaces(File outputDirectory, Collection<String> packages)
-      throws IOException {
-    Collection<MessageIdentifier> topicTypes = Sets.newHashSet();
-    if (packages.size() == 0) {
-      packages = topicDefinitionFileProvider.getPackages();
-    }
-    for (String pkg : packages) {
-      Collection<MessageIdentifier> messageIdentifiers =
-          topicDefinitionFileProvider.getMessageIdentifiersByPackage(pkg);
-      if (messageIdentifiers != null) {
-        topicTypes.addAll(messageIdentifiers);
-      }
-    }
-    for (MessageIdentifier topicType : topicTypes) {
-      String definition = messageDefinitionProviderChain.get(topicType.getType());
-      MessageDeclaration messageDeclaration = new MessageDeclaration(topicType, definition);
-      writeInterface(messageDeclaration, outputDirectory, true);
-    }
-  }
-
-  /**
-   * @param packages
-   *          a list of packages containing the topic types to generate
-   *          interfaces for
-   * @param outputDirectory
-   *          the directory to write the generated interfaces to
-   * @throws IOException
-   */
-  private void writeServiceInterfaces(File outputDirectory, Collection<String> packages)
-      throws IOException {
-    Collection<MessageIdentifier> serviceTypes = Sets.newHashSet();
-    if (packages.size() == 0) {
-      packages = serviceDefinitionFileProvider.getPackages();
-    }
-    for (String pkg : packages) {
-      Collection<MessageIdentifier> messageIdentifiers =
-          serviceDefinitionFileProvider.getMessageIdentifiersByPackage(pkg);
-      if (messageIdentifiers != null) {
-        serviceTypes.addAll(messageIdentifiers);
-      }
-    }
-    for (MessageIdentifier serviceType : serviceTypes) {
-      String definition = messageDefinitionProviderChain.get(serviceType.getType());
-      MessageDeclaration serviceDeclaration =
-          MessageDeclaration.of(serviceType.getType(), definition);
-      writeInterface(serviceDeclaration, outputDirectory, false);
-      List<String> requestAndResponse = MessageDefinitionTupleParser.parse(definition, 2);
-      MessageDeclaration requestDeclaration =
-          MessageDeclaration.of(serviceType.getType() + "Request", requestAndResponse.get(0));
-      MessageDeclaration responseDeclaration =
-          MessageDeclaration.of(serviceType.getType() + "Response", requestAndResponse.get(1));
-      writeInterface(requestDeclaration, outputDirectory, true);
-      writeInterface(responseDeclaration, outputDirectory, true);
-    }
-  }
-
-  private void writeInterface(MessageDeclaration messageDeclaration, File outputDirectory,
-      boolean addConstantsAndMethods) {
-    MessageInterfaceBuilder builder = new MessageInterfaceBuilder();
-    builder.setPackageName(messageDeclaration.getPackage());
-    builder.setInterfaceName(messageDeclaration.getName());
-    builder.setMessageDeclaration(messageDeclaration);
-    builder.setAddConstantsAndMethods(addConstantsAndMethods);
-    try {
-      String content;
-      content = builder.build(messageFactory);
-      File file = new File(outputDirectory, messageDeclaration.getType() + ".java");
-      FileUtils.writeStringToFile(file, content);
-    } catch (Exception e) {
-      System.out.printf("Failed to generate interface for %s.\n", messageDeclaration.getType());
-      e.printStackTrace();
-    }
-  }
-
-  public void generate(File outputDirectory, Collection<String> packages,
-      Collection<File> packagePath) {
-    for (File directory : packagePath) {
-      topicDefinitionFileProvider.addDirectory(directory);
-      serviceDefinitionFileProvider.addDirectory(directory);
-    }
-    topicDefinitionFileProvider.update();
-    serviceDefinitionFileProvider.update();
-    try {
-      writeTopicInterfaces(outputDirectory, packages);
-      writeServiceInterfaces(outputDirectory, packages);
-    } catch (IOException e) {
-      throw new RosRuntimeException(e);
-    }
-  }
-
-  public static void main(String[] args) {
-    List<String> arguments = Lists.newArrayList(args);
-    if (arguments.size() == 0) {
-      arguments.add(".");
-    }
-    String rosPackagePath = System.getenv(EnvironmentVariables.ROS_PACKAGE_PATH);
-    Collection<File> packagePath = Lists.newArrayList();
-    for (String path : rosPackagePath.split(File.pathSeparator)) {
-      File packageDirectory = new File(path);
-      if (packageDirectory.exists()) {
-        packagePath.add(packageDirectory);
-      }
-    }
-    GenerateInterfaces generateInterfaces = new GenerateInterfaces();
-    File outputDirectory = new File(arguments.remove(0));
-    generateInterfaces.generate(outputDirectory, arguments, packagePath);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/GetInstance.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/GetInstance.java
deleted file mode 100644
index 5916b946ee452399bdc9a07a6adc1352545960ac..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/GetInstance.java
+++ /dev/null
@@ -1,25 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-interface GetInstance {
-
-  public Object getInstance();
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/Md5Generator.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/Md5Generator.java
deleted file mode 100644
index 0e78b79969f7911d1e4d8263a714261e75988ab1..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/Md5Generator.java
+++ /dev/null
@@ -1,96 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.base.Preconditions;
-import com.google.common.collect.Lists;
-
-import org.ros.internal.message.definition.MessageDefinitionParser;
-import org.ros.internal.message.definition.MessageDefinitionTupleParser;
-import org.ros.internal.message.definition.MessageDefinitionParser.MessageDefinitionVisitor;
-
-import org.apache.commons.codec.digest.DigestUtils;
-import org.ros.internal.message.field.PrimitiveFieldType;
-import org.ros.message.MessageDefinitionProvider;
-
-import java.util.List;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class Md5Generator {
-
-  private final MessageDefinitionProvider messageDefinitionProvider;
-
-  public Md5Generator(MessageDefinitionProvider messageDefinitionProvider) {
-    this.messageDefinitionProvider = messageDefinitionProvider;
-  }
-
-  public String generate(String messageType) {
-    String messageDefinition = messageDefinitionProvider.get(messageType);
-    Preconditions.checkNotNull(messageDefinition, "No definition for message type: " + messageType);
-    List<String> parts = MessageDefinitionTupleParser.parse(messageDefinition, -1);
-    StringBuilder text = new StringBuilder();
-    for (String part : parts) {
-      text.append(generateText(messageType, part));
-    }
-    return DigestUtils.md5Hex(text.toString());
-  }
-
-  private String generateText(String messageType, String messageDefinition) {
-    final List<String> constants = Lists.newArrayList();
-    final List<String> variables = Lists.newArrayList();
-    MessageDefinitionVisitor visitor = new MessageDefinitionVisitor() {
-      @Override
-      public void variableValue(String type, String name) {
-        if (!PrimitiveFieldType.existsFor(type)) {
-          type = generate(type);
-        }
-        variables.add(String.format("%s %s\n", type, name));
-      }
-
-      @Override
-      public void variableList(String type, int size, String name) {
-        if (!PrimitiveFieldType.existsFor(type)) {
-          String md5Checksum = generate(type);
-          variables.add(String.format("%s %s\n", md5Checksum, name));
-        } else {
-          if (size != -1) {
-            variables.add(String.format("%s[%d] %s\n", type, size, name));
-          } else {
-            variables.add(String.format("%s[] %s\n", type, name));
-          }
-        }
-      }
-
-      @Override
-      public void constantValue(String type, String name, String value) {
-        constants.add(String.format("%s %s=%s\n", type, name, value));
-      }
-    };
-    MessageDefinitionParser messageDefinitionParser = new MessageDefinitionParser(visitor);
-    messageDefinitionParser.parse(messageType, messageDefinition);
-    String text = "";
-    for (String constant : constants) {
-      text += constant;
-    }
-    for (String variable : variables) {
-      text += variable;
-    }
-    return text.trim();
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/Message.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/Message.java
deleted file mode 100644
index 055db8296187e9ae31695954d2f6502512a702ba..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/Message.java
+++ /dev/null
@@ -1,28 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface Message {
-
-  /**
-   * @return returns this {@link Message} as a {@link RawMessage}
-   */
-  RawMessage toRawMessage();
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageBufferPool.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageBufferPool.java
deleted file mode 100644
index 4541596bd11b2f9f33d1ea279a4b492699f35c29..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageBufferPool.java
+++ /dev/null
@@ -1,91 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.apache.commons.pool.ObjectPool;
-import org.apache.commons.pool.PoolableObjectFactory;
-import org.apache.commons.pool.impl.StackObjectPool;
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.exception.RosRuntimeException;
-
-/**
- * A pool of {@link ChannelBuffer}s for serializing and deserializing messages.
- * <p>
- * By contract, {@link ChannelBuffer}s provided by {@link #acquire()} must be
- * returned using {@link #release(ChannelBuffer)}.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageBufferPool {
-
-  private final ObjectPool<ChannelBuffer> pool;
-
-  public MessageBufferPool() {
-    pool = new StackObjectPool<ChannelBuffer>(new PoolableObjectFactory<ChannelBuffer>() {
-      @Override
-      public ChannelBuffer makeObject() throws Exception {
-        return MessageBuffers.dynamicBuffer();
-      }
-
-      @Override
-      public void destroyObject(ChannelBuffer channelBuffer) throws Exception {
-      }
-
-      @Override
-      public boolean validateObject(ChannelBuffer channelBuffer) {
-        return true;
-      }
-
-      @Override
-      public void activateObject(ChannelBuffer channelBuffer) throws Exception {
-      }
-
-      @Override
-      public void passivateObject(ChannelBuffer channelBuffer) throws Exception {
-        channelBuffer.clear();
-      }
-    });
-  }
-
-  /**
-   * Acquired {@link ChannelBuffer}s must be returned using
-   * {@link #release(ChannelBuffer)}.
-   * 
-   * @return an unused {@link ChannelBuffer}
-   */
-  public ChannelBuffer acquire() {
-    try {
-      return pool.borrowObject();
-    } catch (Exception e) {
-      throw new RosRuntimeException(e);
-    }
-  }
-
-  /**
-   * Release a previously acquired {@link ChannelBuffer}.
-   * 
-   * @param channelBuffer
-   *          the {@link ChannelBuffer} to release
-   */
-  public void release(ChannelBuffer channelBuffer) {
-    try {
-      pool.returnObject(channelBuffer);
-    } catch (Exception e) {
-      throw new RosRuntimeException(e);
-    }
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageBuffers.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageBuffers.java
deleted file mode 100644
index a5934ec83e71bf8f30b509c2400f10a95954b870..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageBuffers.java
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.jboss.netty.buffer.ChannelBuffers;
-
-import java.nio.ByteOrder;
-
-/**
- * Provides {@link ChannelBuffer}s for serializing and deserializing messages.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageBuffers {
-
-  static final int ESTIMATED_LENGTH = 256;
-
-  private MessageBuffers() {
-    // Utility class.
-  }
-
-  /**
-   * @return a new {@link ChannelBuffer} for {@link Message} serialization that
-   *         grows dynamically
-   */
-  public static ChannelBuffer dynamicBuffer() {
-    return ChannelBuffers.dynamicBuffer(ByteOrder.LITTLE_ENDIAN, ESTIMATED_LENGTH);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageImpl.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageImpl.java
deleted file mode 100644
index 5f18d7f13fd4d3fbe779963be82ca5dcaa80d419..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageImpl.java
+++ /dev/null
@@ -1,491 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.exception.RosRuntimeException;
-import org.ros.internal.message.context.MessageContext;
-import org.ros.internal.message.field.Field;
-import org.ros.internal.message.field.MessageFieldType;
-import org.ros.internal.message.field.MessageFields;
-import org.ros.message.Duration;
-import org.ros.message.MessageIdentifier;
-import org.ros.message.Time;
-
-import java.util.List;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-class MessageImpl implements RawMessage, GetInstance {
-
-  private final MessageContext messageContext;
-  private final MessageFields messageFields;
-
-  public MessageImpl(MessageContext messageContext) {
-    this.messageContext = messageContext;
-    messageFields = new MessageFields(messageContext);
-  }
-
-  public MessageContext getMessageContext() {
-    return messageContext;
-  }
-
-  public MessageFields getMessageFields() {
-    return messageFields;
-  }
-
-  @Override
-  public RawMessage toRawMessage() {
-    return (RawMessage) this;
-  }
-
-  @Override
-  public MessageIdentifier getIdentifier() {
-    return messageContext.getMessageIdentifer();
-  }
-
-  @Override
-  public String getType() {
-    return messageContext.getType();
-  }
-
-  @Override
-  public String getPackage() {
-    return messageContext.getPackage();
-  }
-
-  @Override
-  public String getName() {
-    return messageContext.getName();
-  }
-
-  @Override
-  public String getDefinition() {
-    return messageContext.getDefinition();
-  }
-
-  @Override
-  public List<Field> getFields() {
-    return messageFields.getFields();
-  }
-
-  @Override
-  public boolean getBool(String name) {
-    return (Boolean) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public boolean[] getBoolArray(String name) {
-    return (boolean[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public Duration getDuration(String name) {
-    return (Duration) messageFields.getFieldValue(name);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public List<Duration> getDurationList(String name) {
-    return (List<Duration>) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public float getFloat32(String name) {
-    return (Float) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public float[] getFloat32Array(String name) {
-    return (float[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public double getFloat64(String name) {
-    return (Double) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public double[] getFloat64Array(String name) {
-    return (double[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short getInt16(String name) {
-    return (Short) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short[] getInt16Array(String name) {
-    return (short[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public int getInt32(String name) {
-    return (Integer) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public int[] getInt32Array(String name) {
-    return (int[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public long getInt64(String name) {
-    return (Long) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public long[] getInt64Array(String name) {
-    return (long[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public byte getInt8(String name) {
-    return (Byte) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public byte[] getInt8Array(String name) {
-    return (byte[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public <T extends Message> T getMessage(String name) {
-    if (messageFields.getField(name).getType() instanceof MessageFieldType) {
-      return messageFields.getField(name).<T>getValue();
-    }
-    throw new RosRuntimeException("Failed to access message field: " + name);
-  }
-
-  @Override
-  public <T extends Message> List<T> getMessageList(String name) {
-    if (messageFields.getField(name).getType() instanceof MessageFieldType) {
-      return messageFields.getField(name).<List<T>>getValue();
-    }
-    throw new RosRuntimeException("Failed to access list field: " + name);
-  }
-
-  @Override
-  public String getString(String name) {
-    return (String) messageFields.getFieldValue(name);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public List<String> getStringList(String name) {
-    return (List<String>) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public Time getTime(String name) {
-    return (Time) messageFields.getFieldValue(name);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public List<Time> getTimeList(String name) {
-    return (List<Time>) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short getUInt16(String name) {
-    return (Short) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short[] getUInt16Array(String name) {
-    return (short[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public int getUInt32(String name) {
-    return (Integer) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public int[] getUInt32Array(String name) {
-    return (int[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public long getUInt64(String name) {
-    return (Long) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public long[] getUInt64Array(String name) {
-    return (long[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short getUInt8(String name) {
-    return (Short) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short[] getUInt8Array(String name) {
-    return (short[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public void setBool(String name, boolean value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setBoolArray(String name, boolean[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setDurationList(String name, List<Duration> value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setDuration(String name, Duration value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setFloat32(String name, float value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setFloat32Array(String name, float[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setFloat64(String name, double value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setFloat64Array(String name, double[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt16(String name, short value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt16Array(String name, short[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt32(String name, int value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt32Array(String name, int[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt64(String name, long value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt64Array(String name, long[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt8(String name, byte value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setInt8Array(String name, byte[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setMessage(String name, Message value) {
-    // TODO(damonkohler): Verify the type of the provided Message?
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setMessageList(String name, List<Message> value) {
-    // TODO(damonkohler): Verify the type of all Messages in the provided list?
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setString(String name, String value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setStringList(String name, List<String> value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setTime(String name, Time value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setTimeList(String name, List<Time> value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt16(String name, short value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt16Array(String name, short[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt32(String name, int value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt32Array(String name, int[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt64(String name, long value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt64Array(String name, long[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt8(String name, byte value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setUInt8Array(String name, byte[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public byte getByte(String name) {
-    return (Byte) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short getChar(String name) {
-    return (Short) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public void setByte(String name, byte value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setChar(String name, short value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setByteArray(String name, byte[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public void setCharArray(String name, short[] value) {
-    messageFields.setFieldValue(name, value);
-  }
-
-  @Override
-  public byte[] getByteArray(String name) {
-    return (byte[]) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public short[] getCharArray(String name) {
-    return (short[]) messageFields.getFieldValue(name);
-  }
-  
-  @Override
-  public ChannelBuffer getChannelBuffer(String name) {
-    return (ChannelBuffer) messageFields.getFieldValue(name);
-  }
-
-  @Override
-  public void setChannelBuffer(String name, ChannelBuffer value) {
-    messageFields.setFieldValue(name, value);
-  }
-  
-  @Override
-  public Object getInstance() {
-    return this;
-  }
-
-  @Override
-  public String toString() {
-    return String.format("MessageImpl<%s>", getType());
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + ((messageContext == null) ? 0 : messageContext.hashCode());
-    result = prime * result + ((messageFields == null) ? 0 : messageFields.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (!(obj instanceof GetInstance))
-      return false;
-    obj = ((GetInstance) obj).getInstance();
-    if (getClass() != obj.getClass())
-      return false;
-    MessageImpl other = (MessageImpl) obj;
-    if (messageContext == null) {
-      if (other.messageContext != null)
-        return false;
-    } else if (!messageContext.equals(other.messageContext))
-      return false;
-    if (messageFields == null) {
-      if (other.messageFields != null)
-        return false;
-    } else if (!messageFields.equals(other.messageFields))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageInterfaceBuilder.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageInterfaceBuilder.java
deleted file mode 100644
index 2247a4574272b316b7a709075717ee0931d3d1b4..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageInterfaceBuilder.java
+++ /dev/null
@@ -1,193 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.base.Preconditions;
-import com.google.common.collect.Sets;
-
-import org.apache.commons.lang.StringEscapeUtils;
-import org.ros.exception.RosRuntimeException;
-import org.ros.internal.message.context.MessageContext;
-import org.ros.internal.message.context.MessageContextProvider;
-import org.ros.internal.message.field.Field;
-import org.ros.internal.message.field.FieldType;
-import org.ros.internal.message.field.MessageFields;
-import org.ros.internal.message.field.PrimitiveFieldType;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageFactory;
-
-import java.util.Set;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageInterfaceBuilder {
-
-  private MessageDeclaration messageDeclaration;
-  private String packageName;
-  private String interfaceName;
-  private boolean addConstantsAndMethods;
-  private String nestedContent;
-
-  // TODO(damonkohler): Upgrade Apache Commons Lang. See
-  // https://issues.apache.org/jira/browse/LANG-437
-  private static String escapeJava(String str) {
-    return StringEscapeUtils.escapeJava(str).replace("\\/", "/").replace("'", "\\'");
-  }
-
-  public MessageDeclaration getMessageDeclaration() {
-    return messageDeclaration;
-  }
-
-  public MessageInterfaceBuilder setMessageDeclaration(MessageDeclaration messageDeclaration) {
-    Preconditions.checkNotNull(messageDeclaration);
-    this.messageDeclaration = messageDeclaration;
-    return this;
-  }
-
-  public String getPackageName() {
-    return packageName;
-  }
-
-  /**
-   * @param packageName
-   *          the package name of the interface or {@code null} if no package
-   *          name should be specified
-   * @return this {@link MessageInterfaceBuilder}
-   */
-  public MessageInterfaceBuilder setPackageName(String packageName) {
-    this.packageName = packageName;
-    return this;
-  }
-
-  public String getInterfaceName() {
-    return interfaceName;
-  }
-
-  public MessageInterfaceBuilder setInterfaceName(String interfaceName) {
-    Preconditions.checkNotNull(interfaceName);
-    this.interfaceName = interfaceName;
-    return this;
-  }
-
-  public boolean getAddConstantsAndMethods() {
-    return addConstantsAndMethods;
-  }
-
-  public void setAddConstantsAndMethods(boolean enabled) {
-    addConstantsAndMethods = enabled;
-  }
-
-  public String getNestedContent() {
-    return nestedContent;
-  }
-
-  public void setNestedContent(String nestedContent) {
-    this.nestedContent = nestedContent;
-  }
-
-  public String build(MessageFactory messageFactory) {
-    Preconditions.checkNotNull(messageDeclaration);
-    Preconditions.checkNotNull(interfaceName);
-    StringBuilder builder = new StringBuilder();
-    if (packageName != null) {
-      builder.append(String.format("package %s;\n\n", packageName));
-    }
-    builder.append(String.format(
-        "public interface %s extends org.ros.internal.message.Message {\n", interfaceName));
-    builder.append(String.format("  static final java.lang.String _TYPE = \"%s\";\n",
-        messageDeclaration.getType()));
-    builder.append(String.format("  static final java.lang.String _DEFINITION = \"%s\";\n",
-        escapeJava(messageDeclaration.getDefinition())));
-    if (addConstantsAndMethods) {
-      MessageContextProvider messageContextProvider = new MessageContextProvider(messageFactory);
-      MessageContext messageContext = messageContextProvider.get(messageDeclaration);
-      appendConstants(messageContext, builder);
-      appendSettersAndGetters(messageContext, builder);
-    }
-    if (nestedContent != null) {
-      builder.append("\n");
-      builder.append(nestedContent);
-    }
-    builder.append("}\n");
-    return builder.toString();
-  }
-
-  @SuppressWarnings("deprecation")
-  private String getJavaValue(PrimitiveFieldType primitiveFieldType, String value) {
-    switch (primitiveFieldType) {
-      case BOOL:
-        return Boolean.valueOf(!value.equals("0") && !value.equals("false")).toString();
-      case FLOAT32:
-        return value + "f";
-      case STRING:
-        return "\"" + escapeJava(value) + "\"";
-      case BYTE:
-      case CHAR:
-      case INT8:
-      case UINT8:
-      case INT16:
-      case UINT16:
-      case INT32:
-      case UINT32:
-      case INT64:
-      case UINT64:
-      case FLOAT64:
-        return value;
-      default:
-        throw new RosRuntimeException("Unsupported PrimitiveFieldType: " + primitiveFieldType);
-    }
-  }
-
-  private void appendConstants(MessageContext messageContext, StringBuilder builder) {
-    MessageFields messageFields = new MessageFields(messageContext);
-    for (Field field : messageFields.getFields()) {
-      if (field.isConstant()) {
-        Preconditions.checkState(field.getType() instanceof PrimitiveFieldType);
-        // We use FieldType and cast back to PrimitiveFieldType below to avoid a
-        // bug in the Sun JDK: http://gs.sun.com/view_bug.do?bug_id=6522780
-        FieldType fieldType = (FieldType) field.getType();
-        String value = getJavaValue((PrimitiveFieldType) fieldType, field.getValue().toString());
-        builder.append(String.format("  static final %s %s = %s;\n", fieldType.getJavaTypeName(),
-            field.getName(), value));
-      }
-    }
-  }
-
-  private void appendSettersAndGetters(MessageContext messageContext, StringBuilder builder) {
-    MessageFields messageFields = new MessageFields(messageContext);
-    Set<String> getters = Sets.newHashSet();
-    for (Field field : messageFields.getFields()) {
-      if (field.isConstant()) {
-        continue;
-      }
-      String type = field.getJavaTypeName();
-      String getter = messageContext.getFieldGetterName(field.getName());
-      String setter = messageContext.getFieldSetterName(field.getName());
-      if (getters.contains(getter)) {
-        // In the case that two or more message fields have the same name except
-        // for capitalization, we only generate a getter and setter pair for the
-        // first one. The following fields will only be accessible via the
-        // RawMessage interface.
-        continue;
-      }
-      getters.add(getter);
-      builder.append(String.format("  %s %s();\n", type, getter));
-      builder.append(String.format("  void %s(%s value);\n", setter, type));
-    }
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageInterfaceClassProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageInterfaceClassProvider.java
deleted file mode 100644
index 544c3159081bbab83b92617e41cd79fba6d601fd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageInterfaceClassProvider.java
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface MessageInterfaceClassProvider {
-
-  /**
-   * @param <T>
-   *          the message interface class type
-   * @param messageType
-   *          the type of message to provide an interface class for
-   * @return the interface class for the specified message type
-   */
-  <T> Class<T> get(String messageType);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageProxyFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageProxyFactory.java
deleted file mode 100644
index cc2e7f21f599abbad1082d18e95c66854392bc1e..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageProxyFactory.java
+++ /dev/null
@@ -1,80 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.base.Preconditions;
-
-import org.ros.internal.message.context.MessageContext;
-import org.ros.internal.message.context.MessageContextProvider;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageFactory;
-
-import java.lang.reflect.Proxy;
-import java.util.concurrent.atomic.AtomicInteger;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageProxyFactory {
-
-  // We can't use the constant here since the rosjava_messages package depends
-  // on rosjava_bootstrap.
-  private static final String HEADER_MESSAGE_TYPE = "std_msgs/Header";
-  private static final String SEQUENCE_FIELD_NAME = "seq";
-  private static final AtomicInteger SEQUENCE_NUMBER = new AtomicInteger(0);
-
-  private final MessageInterfaceClassProvider messageInterfaceClassProvider;
-  private final MessageContextProvider messageContextProvider;
-
-  public MessageProxyFactory(MessageInterfaceClassProvider messageInterfaceClassProvider,
-      MessageFactory messageFactory) {
-    this.messageInterfaceClassProvider = messageInterfaceClassProvider;
-    messageContextProvider = new MessageContextProvider(messageFactory);
-  }
-
-  @SuppressWarnings("unchecked")
-  public <T> T newMessageProxy(MessageDeclaration messageDeclaration) {
-    Preconditions.checkNotNull(messageDeclaration);
-    MessageContext messageContext = messageContextProvider.get(messageDeclaration);
-    MessageImpl messageImpl = new MessageImpl(messageContext);
-    // Header messages are automatically populated with a monotonically
-    // increasing sequence number.
-    if (messageImpl.getType().equals(HEADER_MESSAGE_TYPE)) {
-      messageImpl.setUInt32(SEQUENCE_FIELD_NAME, SEQUENCE_NUMBER.getAndIncrement());
-    }
-    Class<T> messageInterfaceClass =
-        (Class<T>) messageInterfaceClassProvider.get(messageDeclaration.getType());
-    return newProxy(messageInterfaceClass, messageImpl);
-  }
-
-  /**
-   * @param interfaceClass
-   *          the interface class to provide
-   * @param messageImpl
-   *          the instance to proxy
-   * @return a new proxy for {@code implementation} that implements
-   *         {@code interfaceClass}
-   */
-  @SuppressWarnings("unchecked")
-  private <T> T newProxy(Class<T> interfaceClass, final MessageImpl messageImpl) {
-    ClassLoader classLoader = messageImpl.getClass().getClassLoader();
-    Class<?>[] interfaces = new Class<?>[] { interfaceClass, GetInstance.class };
-    MessageProxyInvocationHandler invocationHandler =
-        new MessageProxyInvocationHandler(messageImpl);
-    return (T) Proxy.newProxyInstance(classLoader, interfaces, invocationHandler);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageProxyInvocationHandler.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageProxyInvocationHandler.java
deleted file mode 100644
index 2f1c2e2b65acba73d5d39377d04fcf9c2b66793b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/MessageProxyInvocationHandler.java
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.ros.internal.message.field.Field;
-import org.ros.internal.message.field.MessageFields;
-
-import java.lang.reflect.InvocationHandler;
-import java.lang.reflect.Method;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageProxyInvocationHandler implements InvocationHandler {
-
-  private final MessageImpl messageImpl;
-
-  MessageProxyInvocationHandler(MessageImpl messageImpl) {
-    this.messageImpl = messageImpl;
-  }
-
-  @Override
-  public Object invoke(Object proxy, Method method, Object[] args) throws Throwable {
-    String methodName = method.getName();
-    MessageFields mesageFields = messageImpl.getMessageFields();
-    Field getterField = mesageFields.getGetterField(methodName);
-    if (getterField != null) {
-      return getterField.getValue();
-    }
-    Field setterField = mesageFields.getSetterField(methodName);
-    if (setterField != null) {
-      setterField.setValue(args[0]);
-      return null;
-    }
-    return method.invoke(messageImpl, args);
-  }
-}
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/RawMessage.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/RawMessage.java
deleted file mode 100644
index 999db7a076d3cfe33e4cef3c1798b329d084b61a..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/RawMessage.java
+++ /dev/null
@@ -1,207 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.internal.message.field.Field;
-import org.ros.message.Duration;
-import org.ros.message.MessageIdentifier;
-import org.ros.message.Time;
-
-import java.util.List;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface RawMessage extends Message {
-
-  boolean getBool(String name);
-
-  boolean[] getBoolArray(String name);
-
-  /**
-   * @deprecated replaced by {@link #getInt8(String)}
-   */
-  byte getByte(String name);
-
-  /**
-   * @deprecated replaced by {@link #getInt8Array(String)}
-   */
-  byte[] getByteArray(String name);
-
-  /**
-   * @deprecated replaced by {@link #getUInt8(String)}
-   */
-  short getChar(String name);
-
-  /**
-   * @deprecated replaced by {@link #getUInt8Array(String)}
-   */
-  short[] getCharArray(String name);
-
-  String getDefinition();
-
-  Duration getDuration(String name);
-
-  List<Duration> getDurationList(String name);
-
-  List<Field> getFields();
-
-  float getFloat32(String name);
-
-  float[] getFloat32Array(String name);
-
-  double getFloat64(String name);
-
-  double[] getFloat64Array(String name);
-
-  MessageIdentifier getIdentifier();
-
-  short getInt16(String name);
-
-  short[] getInt16Array(String name);
-
-  int getInt32(String name);
-
-  int[] getInt32Array(String name);
-
-  long getInt64(String name);
-
-  long[] getInt64Array(String name);
-
-  byte getInt8(String name);
-
-  byte[] getInt8Array(String name);
-
-  <T extends Message> T getMessage(String name);
-
-  <T extends Message> List<T> getMessageList(String name);
-
-  String getName();
-
-  String getPackage();
-
-  String getString(String name);
-
-  List<String> getStringList(String name);
-
-  Time getTime(String name);
-
-  List<Time> getTimeList(String name);
-
-  String getType();
-
-  short getUInt16(String name);
-
-  short[] getUInt16Array(String name);
-
-  int getUInt32(String name);
-
-  int[] getUInt32Array(String name);
-
-  long getUInt64(String name);
-
-  long[] getUInt64Array(String name);
-
-  short getUInt8(String name);
-
-  short[] getUInt8Array(String name);
-
-  void setBool(String name, boolean value);
-
-  void setBoolArray(String name, boolean[] value);
-
-  /**
-   * @deprecated replaced by {@link #setInt8(String, byte)}
-   */
-  void setByte(String name, byte value);
-
-  /**
-   * @deprecated replaced by {@link #setInt8Array(String, byte[])}
-   */
-  void setByteArray(String name, byte[] value);
-
-  /**
-   * @deprecated replaced by {@link #setUInt8(String, byte)}
-   */
-  void setChar(String name, short value);
-
-  /**
-   * @deprecated replaced by {@link #setUInt8Array(String, byte[])}
-   */
-  void setCharArray(String name, short[] value);
-
-  void setDuration(String name, Duration value);
-
-  void setDurationList(String name, List<Duration> value);
-
-  void setFloat32(String name, float value);
-
-  void setFloat32Array(String name, float[] value);
-
-  void setFloat64(String name, double value);
-
-  void setFloat64Array(String name, double[] value);
-
-  void setInt16(String name, short value);
-
-  void setInt16Array(String name, short[] value);
-
-  void setInt32(String name, int value);
-
-  void setInt32Array(String name, int[] value);
-
-  void setInt64(String name, long value);
-
-  void setInt64Array(String name, long[] value);
-
-  void setInt8(String name, byte value);
-
-  void setInt8Array(String name, byte[] value);
-
-  void setMessage(String name, Message value);
-
-  void setMessageList(String name, List<Message> value);
-
-  void setString(String name, String value);
-
-  void setStringList(String name, List<String> value);
-
-  void setTime(String name, Time value);
-
-  void setTimeList(String name, List<Time> value);
-
-  void setUInt16(String name, short value);
-
-  void setUInt16Array(String name, short[] value);
-
-  void setUInt32(String name, int value);
-
-  void setUInt32Array(String name, int[] value);
-
-  void setUInt64(String name, long value);
-
-  void setUInt64Array(String name, long[] value);
-
-  void setUInt8(String name, byte value);
-
-  void setUInt8Array(String name, byte[] value);
-
-  void setChannelBuffer(String name, ChannelBuffer value);
-
-  ChannelBuffer getChannelBuffer(String name);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/StringFileProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/StringFileProvider.java
deleted file mode 100644
index 8d50c2b2bda741378cf3d2b9aeaababcb160d9c4..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/StringFileProvider.java
+++ /dev/null
@@ -1,130 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.base.Preconditions;
-import com.google.common.collect.ImmutableMap;
-import com.google.common.collect.Lists;
-import com.google.common.collect.Maps;
-import com.google.common.collect.Sets;
-
-import org.apache.commons.io.DirectoryWalker;
-import org.apache.commons.io.FileUtils;
-import org.apache.commons.io.filefilter.FileFilterUtils;
-import org.apache.commons.io.filefilter.IOFileFilter;
-import org.ros.exception.RosRuntimeException;
-
-import java.io.File;
-import java.io.FileFilter;
-import java.io.IOException;
-import java.util.Collection;
-import java.util.Map;
-import java.util.NoSuchElementException;
-import java.util.Set;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class StringFileProvider {
-
-  private final Collection<File> directories;
-  private final Map<File, String> strings;
-  private final StringFileDirectoryWalker stringFileDirectoryWalker;
-
-  private final class StringFileDirectoryWalker extends DirectoryWalker {
-    
-    private final Set<File> directories;
-
-    private StringFileDirectoryWalker(FileFilter filter, int depthLimit) {
-      super(filter, depthLimit);
-      directories = Sets.newHashSet();
-    }
-    
-    // TODO(damonkohler): Update Apache Commons IO to the latest version.
-    @SuppressWarnings("rawtypes")
-    @Override
-    protected boolean handleDirectory(File directory, int depth, Collection results)
-        throws IOException {
-      File canonicalDirectory = directory.getCanonicalFile();
-      if (directories.contains(canonicalDirectory)) {
-        return false;
-      }
-      directories.add(canonicalDirectory);
-      return true;
-    }
-
-    @SuppressWarnings("rawtypes")
-    @Override
-    protected void handleFile(File file, int depth, Collection results) {
-      String content;
-      try {
-        content = FileUtils.readFileToString(file, "US-ASCII");
-      } catch (IOException e) {
-        throw new RosRuntimeException(e);
-      }
-      strings.put(file, content);
-    }
-
-    public void update(File directory) {
-      try {
-        walk(directory, null);
-      } catch (IOException e) {
-        throw new RosRuntimeException(e);
-      }
-    }
-  }
-
-  public StringFileProvider(IOFileFilter ioFileFilter) {
-    directories = Lists.newArrayList();
-    strings = Maps.newConcurrentMap();
-    IOFileFilter directoryFilter = FileFilterUtils.directoryFileFilter();
-    FileFilter fileFilter = FileFilterUtils.orFileFilter(directoryFilter, ioFileFilter);
-    stringFileDirectoryWalker = new StringFileDirectoryWalker(fileFilter, -1);
-  }
-
-  public void update() {
-    for (File directory : directories) {
-      stringFileDirectoryWalker.update(directory);
-    }
-  }
-
-  /**
-   * Adds a new directory to be scanned for topic definition files.
-   * 
-   * @param directory
-   *          the directory to add
-   */
-  public void addDirectory(File directory) {
-    Preconditions.checkArgument(directory.isDirectory());
-    directories.add(directory);
-  }
-
-  public Map<File, String> getStrings() {
-    return ImmutableMap.copyOf(strings);
-  }
-
-  public String get(File file) {
-    if (!has(file)) {
-      throw new NoSuchElementException("File does not exist: " + file);
-    }
-    return strings.get(file);
-  }
-
-  public boolean has(File file) {
-    return strings.containsKey(file);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/StringResourceProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/StringResourceProvider.java
deleted file mode 100644
index 322f635cc53989dd46708b8f65fce3be9fa86dec..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/StringResourceProvider.java
+++ /dev/null
@@ -1,73 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message;
-
-import com.google.common.collect.ImmutableMap;
-import com.google.common.collect.Maps;
-
-import org.ros.exception.RosRuntimeException;
-
-import java.io.IOException;
-import java.io.InputStream;
-import java.nio.charset.Charset;
-import java.util.Map;
-import java.util.NoSuchElementException;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class StringResourceProvider {
-
-  private final Map<String, String> cache;
-
-  public StringResourceProvider() {
-    cache = Maps.newConcurrentMap();
-  }
-
-  public String get(String resourceName) {
-    if (!has(resourceName)) {
-      throw new NoSuchElementException("Resource does not exist: " + resourceName);
-    }
-    if (!cache.containsKey(resourceName)) {
-      InputStream in = getClass().getResourceAsStream(resourceName);
-      StringBuilder out = new StringBuilder();
-      Charset charset = Charset.forName("US-ASCII");
-      byte[] buffer = new byte[8192];
-      try {
-        for (int bytesRead; (bytesRead = in.read(buffer)) != -1;) {
-          out.append(new String(buffer, 0, bytesRead, charset));
-        }
-      } catch (IOException e) {
-        throw new RosRuntimeException("Failed to read resource: " + resourceName, e);
-      }
-      cache.put(resourceName, out.toString());
-    }
-    return cache.get(resourceName);
-  }
-
-  public boolean has(String resourceName) {
-    return cache.containsKey(resourceName) || getClass().getResource(resourceName) != null;
-  }
-
-  public Map<String, String> getCachedStrings() {
-    return ImmutableMap.copyOf(cache);
-  }
-
-  public void addStringToCache(String resourceName, String resourceContent) {
-    cache.put(resourceName, resourceContent);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContext.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContext.java
deleted file mode 100644
index 11f4a2b49c278ed73a9a8df9d31a3271565fe3b5..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContext.java
+++ /dev/null
@@ -1,144 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.context;
-
-import com.google.common.collect.Lists;
-import com.google.common.collect.Maps;
-
-import org.ros.internal.message.field.FieldFactory;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageFactory;
-import org.ros.message.MessageIdentifier;
-
-import java.util.Collections;
-import java.util.List;
-import java.util.Map;
-
-/**
- * Encapsulates the immutable metadata that describes a message type.
- * <p>
- * Note that this class is not thread safe.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageContext {
-
-  private final MessageDeclaration messageDeclaration;
-  private final MessageFactory messageFactory;
-  private final Map<String, FieldFactory> fieldFactories;
-  private final Map<String, String> fieldGetterNames;
-  private final Map<String, String> fieldSetterNames;
-  private final List<String> fieldNames;
-
-  public MessageContext(MessageDeclaration messageDeclaration, MessageFactory messageFactory) {
-    this.messageDeclaration = messageDeclaration;
-    this.messageFactory = messageFactory;
-    this.fieldFactories = Maps.newHashMap();
-    this.fieldGetterNames = Maps.newHashMap();
-    this.fieldSetterNames = Maps.newHashMap();
-    this.fieldNames = Lists.newArrayList();
-  }
-
-  public MessageFactory getMessageFactory() {
-    return messageFactory;
-  }
-
-  public MessageIdentifier getMessageIdentifer() {
-    return messageDeclaration.getMessageIdentifier();
-  }
-
-  public String getType() {
-    return messageDeclaration.getType();
-  }
-
-  public String getPackage() {
-    return messageDeclaration.getPackage();
-  }
-
-  public String getName() {
-    return messageDeclaration.getName();
-  }
-
-  public String getDefinition() {
-    return messageDeclaration.getDefinition();
-  }
-
-  public void addFieldFactory(String name, FieldFactory fieldFactory) {
-    fieldFactories.put(name, fieldFactory);
-    fieldGetterNames.put(name, "get" + getJavaName(name));
-    fieldSetterNames.put(name, "set" + getJavaName(name));
-    fieldNames.add(name);
-  }
-
-  private String getJavaName(String name) {
-    String[] parts = name.split("_");
-    StringBuilder fieldName = new StringBuilder();
-    for (String part : parts) {
-      fieldName.append(part.substring(0, 1).toUpperCase() + part.substring(1));
-    }
-    return fieldName.toString();
-  }
-
-  public boolean hasField(String name) {
-    // O(1) instead of an O(n) check against the list of field names.
-    return fieldFactories.containsKey(name);
-  }
-
-  public String getFieldGetterName(String name) {
-    return fieldGetterNames.get(name);
-  }
-
-  public String getFieldSetterName(String name) {
-    return fieldSetterNames.get(name);
-  }
-
-  public FieldFactory getFieldFactory(String name) {
-    return fieldFactories.get(name);
-  }
-
-  /**
-   * @return a {@link List} of field names in the order they were added
-   */
-  public List<String> getFieldNames() {
-    return Collections.unmodifiableList(fieldNames);
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + ((messageDeclaration == null) ? 0 : messageDeclaration.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    MessageContext other = (MessageContext) obj;
-    if (messageDeclaration == null) {
-      if (other.messageDeclaration != null)
-        return false;
-    } else if (!messageDeclaration.equals(other.messageDeclaration))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContextBuilder.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContextBuilder.java
deleted file mode 100644
index dd14924dd952b83f4cbe3eb81cd83823e394330f..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContextBuilder.java
+++ /dev/null
@@ -1,85 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.context;
-
-import com.google.common.base.Preconditions;
-
-import org.ros.internal.message.definition.MessageDefinitionParser.MessageDefinitionVisitor;
-import org.ros.internal.message.field.Field;
-import org.ros.internal.message.field.FieldFactory;
-import org.ros.internal.message.field.FieldType;
-import org.ros.internal.message.field.MessageFieldType;
-import org.ros.internal.message.field.PrimitiveFieldType;
-import org.ros.message.MessageIdentifier;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-class MessageContextBuilder implements MessageDefinitionVisitor {
-
-  private final MessageContext messageContext;
-
-  public MessageContextBuilder(MessageContext context) {
-    this.messageContext = context;
-  }
-
-  private FieldType getFieldType(String type) {
-    Preconditions.checkArgument(!type.equals(messageContext.getType()),
-        "Message definitions may not be self-referential.");
-    FieldType fieldType;
-    if (PrimitiveFieldType.existsFor(type)) {
-      fieldType = PrimitiveFieldType.valueOf(type.toUpperCase());
-    } else {
-      fieldType =
-          new MessageFieldType(MessageIdentifier.of(type), messageContext.getMessageFactory());
-    }
-    return fieldType;
-  }
-
-  @Override
-  public void variableValue(String type, final String name) {
-    final FieldType fieldType = getFieldType(type);
-    messageContext.addFieldFactory(name, new FieldFactory() {
-      @Override
-      public Field create() {
-        return fieldType.newVariableValue(name);
-      }
-    });
-  }
-
-  @Override
-  public void variableList(String type, final int size, final String name) {
-    final FieldType fieldType = getFieldType(type);
-    messageContext.addFieldFactory(name, new FieldFactory() {
-      @Override
-      public Field create() {
-        return fieldType.newVariableList(name, size);
-      }
-    });
-  }
-
-  @Override
-  public void constantValue(String type, final String name, final String value) {
-    final FieldType fieldType = getFieldType(type);
-    messageContext.addFieldFactory(name, new FieldFactory() {
-      @Override
-      public Field create() {
-        return fieldType.newConstantValue(name, fieldType.parseFromString(value));
-      }
-    });
-  }
-}
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContextProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContextProvider.java
deleted file mode 100644
index 0782970a25062dce40105d74f90bd5101c97d588..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/context/MessageContextProvider.java
+++ /dev/null
@@ -1,55 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.context;
-
-import com.google.common.base.Preconditions;
-import com.google.common.collect.Maps;
-
-import org.ros.internal.message.definition.MessageDefinitionParser;
-import org.ros.internal.message.definition.MessageDefinitionParser.MessageDefinitionVisitor;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageFactory;
-
-import java.util.Map;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageContextProvider {
-
-  private final Map<MessageDeclaration, MessageContext> cache;
-  private final MessageFactory messageFactory;
-
-  public MessageContextProvider(MessageFactory messageFactory) {
-    Preconditions.checkNotNull(messageFactory);
-    this.messageFactory = messageFactory;
-    cache = Maps.newConcurrentMap();
-  }
-
-  public MessageContext get(MessageDeclaration messageDeclaration) {
-    MessageContext messageContext = cache.get(messageDeclaration);
-    if (messageContext == null) {
-      messageContext = new MessageContext(messageDeclaration, messageFactory);
-      MessageDefinitionVisitor visitor = new MessageContextBuilder(messageContext);
-      MessageDefinitionParser messageDefinitionParser = new MessageDefinitionParser(visitor);
-      messageDefinitionParser.parse(messageDeclaration.getType(),
-          messageDeclaration.getDefinition());
-      cache.put(messageDeclaration, messageContext);
-    }
-    return messageContext;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionFileProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionFileProvider.java
deleted file mode 100644
index 4aa0389140c6c9d698b3e481a590dd2d1ea264e3..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionFileProvider.java
+++ /dev/null
@@ -1,114 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.definition;
-
-import com.google.common.collect.Maps;
-
-import org.ros.internal.message.StringFileProvider;
-
-import org.apache.commons.io.FilenameUtils;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageIdentifier;
-
-import java.io.File;
-import java.util.Collection;
-import java.util.HashSet;
-import java.util.Map;
-import java.util.Map.Entry;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageDefinitionFileProvider implements MessageDefinitionProvider {
-
-  private final StringFileProvider stringFileProvider;
-  private final Map<String, Collection<MessageIdentifier>> messageIdentifiers;
-  private final Map<String, String> definitions;
-
-  public MessageDefinitionFileProvider(StringFileProvider stringFileProvider) {
-    this.stringFileProvider = stringFileProvider;
-    messageIdentifiers = Maps.newConcurrentMap();
-    definitions = Maps.newConcurrentMap();
-  }
-
-  private static String getParent(String filename) {
-    return FilenameUtils.getFullPathNoEndSeparator(filename);
-  }
-
-  protected static String getParentBaseName(String filename) {
-    return FilenameUtils.getBaseName(getParent(filename));
-  }
-
-  private static MessageIdentifier fileToMessageIdentifier(File file) {
-    String filename = file.getAbsolutePath();
-    String name = FilenameUtils.getBaseName(filename);
-    String pkg = getParentBaseName(getParent(filename));
-    return MessageIdentifier.of(pkg, name);
-  }
-
-  private void addDefinition(File file, String definition) {
-    MessageIdentifier topicType = fileToMessageIdentifier(file);
-    if (definitions.containsKey(topicType.getType())) {
-      // First definition wins.
-      return;
-    }
-    definitions.put(topicType.getType(), definition);
-    if (!messageIdentifiers.containsKey(topicType.getPackage())) {
-      messageIdentifiers.put(topicType.getPackage(), new HashSet<MessageIdentifier>());
-    }
-    messageIdentifiers.get(topicType.getPackage()).add(topicType);
-  }
-
-  /**
-   * Updates the topic definition cache.
-   * 
-   * @see StringFileProvider#update()
-   */
-  public void update() {
-    stringFileProvider.update();
-    for (Entry<File, String> entry : stringFileProvider.getStrings().entrySet()) {
-      addDefinition(entry.getKey(), entry.getValue());
-    }
-  }
-
-  /**
-   * @see StringFileProvider#addDirectory(File)
-   */
-  public void addDirectory(File directory) {
-    stringFileProvider.addDirectory(directory);
-  }
-
-  @Override
-  public Collection<String> getPackages() {
-    return messageIdentifiers.keySet();
-  }
-
-  @Override
-  public Collection<MessageIdentifier> getMessageIdentifiersByPackage(String pkg) {
-    return messageIdentifiers.get(pkg);
-  }
-
-  @Override
-  public String get(String type) {
-    return definitions.get(type);
-  }
-
-  @Override
-  public boolean has(String type) {
-    return definitions.containsKey(type);
-  }
-}
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionParser.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionParser.java
deleted file mode 100644
index a5ef3be29c23a27755bbe066bc72a1a3ae989a92..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionParser.java
+++ /dev/null
@@ -1,176 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.definition;
-
-import com.google.common.base.Preconditions;
-
-import org.ros.exception.RosRuntimeException;
-import org.ros.internal.message.field.PrimitiveFieldType;
-
-import java.io.BufferedReader;
-import java.io.IOException;
-import java.io.StringReader;
-
-/**
- * Parses message definitions and invokes a {@link MessageDefinitionVisitor} for
- * each field.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageDefinitionParser {
-
-  private final MessageDefinitionVisitor visitor;
-
-  public interface MessageDefinitionVisitor {
-    /**
-     * Called for each constant in the message definition.
-     * 
-     * @param type
-     *          the type of the constant
-     * @param name
-     *          the name of the constant
-     * @param value
-     *          the value of the constant
-     */
-    void constantValue(String type, String name, String value);
-
-    /**
-     * Called for each scalar in the message definition.
-     * 
-     * @param type
-     *          the type of the scalar
-     * @param name
-     *          the name of the scalar
-     */
-    void variableValue(String type, String name);
-
-    /**
-     * Called for each array in the message definition.
-     * 
-     * @param type
-     *          the type of the array
-     * @param size
-     *          the size of the array or -1 if the size is unbounded
-     * @param name
-     *          the name of the array
-     */
-    void variableList(String type, int size, String name);
-  }
-
-  /**
-   * @param visitor
-   *          the {@link MessageDefinitionVisitor} that will be called for each
-   *          field
-   */
-  public MessageDefinitionParser(MessageDefinitionVisitor visitor) {
-    this.visitor = visitor;
-  }
-
-  /**
-   * Parses the message definition
-   * 
-   * @param messageType
-   *          the type of message defined (e.g. std_msgs/String)
-   * @param messageDefinition
-   *          the message definition (e.g. "string data")
-   */
-  public void parse(String messageType, String messageDefinition) {
-    Preconditions.checkNotNull(messageType);
-    Preconditions.checkNotNull(messageDefinition);
-    BufferedReader reader = new BufferedReader(new StringReader(messageDefinition));
-    String line;
-    try {
-      while (true) {
-        line = reader.readLine();
-        if (line == null) {
-          break;
-        }
-        line = line.trim();
-        if (line.startsWith("#")) {
-          continue;
-        }
-        if (line.length() > 0) {
-          parseField(messageType, line);
-        }
-      }
-    } catch (IOException e) {
-      throw new RosRuntimeException(e);
-    }
-  }
-
-  private void parseField(String messageType, String fieldDefinition) {
-    // TODO(damonkohler): Regex input validation.
-    String[] typeAndName = fieldDefinition.split("\\s+", 2);
-    Preconditions.checkState(typeAndName.length == 2,
-        String.format("Invalid field definition: \"%s\"", fieldDefinition));
-    String type = typeAndName[0];
-    String name = typeAndName[1];
-    String value = null;
-    if (name.contains("=") && (!name.contains("#") || name.indexOf('#') > name.indexOf('='))) {
-      String[] nameAndValue = name.split("=", 2);
-      name = nameAndValue[0].trim();
-      value = nameAndValue[1].trim();
-    } else if (name.contains("#")) {
-      // Stripping comments from constants is deferred until we also know the
-      // type since strings are handled differently.
-      Preconditions.checkState(!name.startsWith("#"), String.format(
-          "Fields must define a name. Field definition in %s was: \"%s\"", messageType,
-          fieldDefinition));
-      name = name.substring(0, name.indexOf('#'));
-      name = name.trim();
-    }
-    boolean array = false;
-    int size = -1;
-    if (type.endsWith("]")) {
-      int leftBracketIndex = type.lastIndexOf('[');
-      int rightBracketIndex = type.lastIndexOf(']');
-      array = true;
-      if (rightBracketIndex - leftBracketIndex > 1) {
-        size = Integer.parseInt(type.substring(leftBracketIndex + 1, rightBracketIndex));
-      }
-      type = type.substring(0, leftBracketIndex);
-    }
-    if (type.equals("Header")) {
-      // The header field is treated as though it were a built-in and silently
-      // expanded to "std_msgs/Header."
-      Preconditions.checkState(name.equals("header"), "Header field must be named \"header.\"");
-      type = "std_msgs/Header";
-    } else if (!PrimitiveFieldType.existsFor(type) && !type.contains("/")) {
-      // Handle package relative message names.
-      type = messageType.substring(0, messageType.lastIndexOf('/') + 1) + type;
-    }
-    if (value != null) {
-      if (array) {
-        // TODO(damonkohler): Handle array constants?
-        throw new UnsupportedOperationException("Array constants are not supported.");
-      }
-      // Comments inline with string constants are treated as data.
-      if (!type.equals(PrimitiveFieldType.STRING.getName()) && value.contains("#")) {
-        Preconditions.checkState(!value.startsWith("#"), "Constants must define a value.");
-        value = value.substring(0, value.indexOf('#'));
-        value = value.trim();
-      }
-      visitor.constantValue(type, name, value);
-    } else {
-      if (array) {
-        visitor.variableList(type, size, name);
-      } else {
-        visitor.variableValue(type, name);
-      }
-    }
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionProviderChain.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionProviderChain.java
deleted file mode 100644
index 9bf71de2852554d5fd9244e1d1f70ed01c5b248c..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionProviderChain.java
+++ /dev/null
@@ -1,86 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.definition;
-
-import com.google.common.collect.Lists;
-import com.google.common.collect.Sets;
-
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageIdentifier;
-
-import java.util.Collection;
-import java.util.NoSuchElementException;
-import java.util.Set;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageDefinitionProviderChain implements MessageDefinitionProvider {
-
-  private final Collection<MessageDefinitionProvider> messageDefinitionProviders;
-
-  public MessageDefinitionProviderChain() {
-    messageDefinitionProviders = Lists.newArrayList();
-  }
-
-  public void addMessageDefinitionProvider(MessageDefinitionProvider messageDefinitionProvider) {
-    messageDefinitionProviders.add(messageDefinitionProvider);
-  }
-
-  @Override
-  public String get(String messageType) {
-    for (MessageDefinitionProvider messageDefinitionProvider : messageDefinitionProviders) {
-      if (messageDefinitionProvider.has(messageType)) {
-        return messageDefinitionProvider.get(messageType);
-      }
-    }
-    throw new NoSuchElementException("No message definition available for: " + messageType);
-  }
-
-  @Override
-  public boolean has(String messageType) {
-    for (MessageDefinitionProvider messageDefinitionProvider : messageDefinitionProviders) {
-      if (messageDefinitionProvider.has(messageType)) {
-        return true;
-      }
-    }
-    return false;
-  }
-
-  @Override
-  public Collection<String> getPackages() {
-    Set<String> result = Sets.newHashSet();
-    for (MessageDefinitionProvider messageDefinitionProvider : messageDefinitionProviders) {
-      Collection<String> packages = messageDefinitionProvider.getPackages();
-      result.addAll(packages);
-    }
-    return result;
-  }
-
-  @Override
-  public Collection<MessageIdentifier> getMessageIdentifiersByPackage(String pkg) {
-    Set<MessageIdentifier> result = Sets.newHashSet();
-    for (MessageDefinitionProvider messageDefinitionProvider : messageDefinitionProviders) {
-      Collection<MessageIdentifier> messageIdentifiers =
-          messageDefinitionProvider.getMessageIdentifiersByPackage(pkg);
-      if (messageIdentifiers != null) {
-        result.addAll(messageIdentifiers);
-      }
-    }
-    return result;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionReflectionProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionReflectionProvider.java
deleted file mode 100644
index b0df12cb1b329330441e7a23ee8b4de63b6939af..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionReflectionProvider.java
+++ /dev/null
@@ -1,88 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.definition;
-
-import com.google.common.annotations.VisibleForTesting;
-import com.google.common.collect.Maps;
-
-import org.ros.exception.RosRuntimeException;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageIdentifier;
-
-import java.util.Collection;
-import java.util.Map;
-
-/**
- * A {@link MessageDefinitionProvider} that uses reflection to load the message
- * definition {@link String} from a generated interface {@link Class}.
- * <p>
- * Note that this {@link MessageDefinitionProvider} does not support enumerating
- * messages by package.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageDefinitionReflectionProvider implements MessageDefinitionProvider {
-
-  private static final String DEFINITION_FIELD = "_DEFINITION";
-
-  private final Map<String, String> cache;
-
-  public MessageDefinitionReflectionProvider() {
-    cache = Maps.newConcurrentMap();
-  }
-
-  @Override
-  public String get(String messageType) {
-    String messageDefinition = cache.get(messageType);
-    if (messageDefinition == null) {
-      String className = messageType.replace("/", ".");
-      try {
-        Class<?> loadedClass = getClass().getClassLoader().loadClass(className);
-        messageDefinition = (String) loadedClass.getDeclaredField(DEFINITION_FIELD).get(null);
-        cache.put(messageType, messageDefinition);
-      } catch (Exception e) {
-        throw new RosRuntimeException(e);
-      }
-    }
-    return messageDefinition;
-  }
-
-  @Override
-  public boolean has(String messageType) {
-    try {
-      get(messageType);
-    } catch (Exception e) {
-      return false;
-    }
-    return true;
-  }
-
-  @Override
-  public Collection<String> getPackages() {
-    throw new UnsupportedOperationException();
-  }
-
-  @Override
-  public Collection<MessageIdentifier> getMessageIdentifiersByPackage(String pkg) {
-    throw new UnsupportedOperationException();
-  }
-
-  @VisibleForTesting
-  public void add(String messageType, String messageDefinition) {
-    cache.put(messageType, messageDefinition);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionTupleParser.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionTupleParser.java
deleted file mode 100644
index e7cdc9fb29b531438152d6d48d659c9a0ad61570..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/definition/MessageDefinitionTupleParser.java
+++ /dev/null
@@ -1,68 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.definition;
-
-import com.google.common.base.Preconditions;
-import com.google.common.collect.Lists;
-
-import java.util.List;
-
-/**
- * Splits message definitions tuples (e.g. service definitions) into separate
- * message definitions.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageDefinitionTupleParser {
-
-  private static final String SEPARATOR = "---";
-
-  /**
-   * Splits the message definition tuple into a {@link List} of message
-   * definitions. Split message definitions may be empty (e.g. std_srvs/Empty).
-   * 
-   * @param definition
-   *          the message definition tuple
-   * @param size
-   *          the expected tuple size, or -1 to ignore this requirement
-   * @return a {@link List} of the specified size
-   */
-  public static List<String> parse(String definition, int size) {
-    Preconditions.checkNotNull(definition);
-    List<String> definitions = Lists.newArrayList();
-    StringBuilder current = new StringBuilder();
-    for (String line : definition.split("\n")) {
-      if (line.startsWith(SEPARATOR)) {
-        definitions.add(current.toString());
-        current = new StringBuilder();
-        continue;
-      }
-      current.append(line);
-      current.append("\n");
-    }
-    if (current.length() > 0) {
-      current.deleteCharAt(current.length() - 1);
-    }
-    definitions.add(current.toString());
-    Preconditions.checkState(size == -1 || definitions.size() <= size,
-        String.format("Message tuple exceeds expected size: %d > %d", definitions.size(), size));
-    while (definitions.size() < size) {
-      definitions.add("");
-    }
-    return definitions;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/BooleanArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/BooleanArrayField.java
deleted file mode 100644
index 75a9fe174d3cd4bffafce7c9163b60abf7586d07..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/BooleanArrayField.java
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class BooleanArrayField extends Field {
-
-  private final int size;
-
-  private boolean[] value;
-
-  public static BooleanArrayField newVariable(String name, int size) {
-    return new BooleanArrayField(PrimitiveFieldType.BOOL, name, size);
-  }
-
-  private BooleanArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new boolean[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public boolean[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((boolean[]) value).length == size);
-    this.value = (boolean[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (boolean v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new boolean[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readByte() == 1;
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "BooleanArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    BooleanArrayField other = (BooleanArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ByteArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ByteArrayField.java
deleted file mode 100644
index 02e08bfbc58a7ed452cdb2b951a4cd2926090219..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ByteArrayField.java
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ByteArrayField extends Field {
-
-  private final int size;
-
-  private byte[] value;
-
-  public static ByteArrayField newVariable(FieldType type, String name, int size) {
-    return new ByteArrayField(type, name, size);
-  }
-
-  private ByteArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new byte[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public byte[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((byte[]) value).length == size);
-    this.value = (byte[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (byte v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new byte[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readByte();
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "ByteArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    ByteArrayField other = (ByteArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ChannelBufferField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ChannelBufferField.java
deleted file mode 100644
index a13f542590d4558355b6948ba9d367ad157959b2..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ChannelBufferField.java
+++ /dev/null
@@ -1,118 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.internal.message.MessageBuffers;
-
-import java.nio.ByteOrder;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ChannelBufferField extends Field {
-
-  private final int size;
-
-  private ChannelBuffer value;
-
-  public static ChannelBufferField newVariable(FieldType type, String name, int size) {
-    return new ChannelBufferField(type, name, size);
-  }
-
-  private ChannelBufferField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    value = MessageBuffers.dynamicBuffer();
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public ChannelBuffer getValue() {
-    // Return a defensive duplicate. Unlike with copy(), duplicated
-    // ChannelBuffers share the same backing array, so this is relatively cheap.
-    return value.duplicate();
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(((ChannelBuffer) value).order() == ByteOrder.LITTLE_ENDIAN);
-    Preconditions.checkArgument(size < 0 || ((ChannelBuffer) value).readableBytes() == size);
-    this.value = (ChannelBuffer) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.readableBytes());
-    }
-    // By specifying the start index and length we avoid modifying value's
-    // indices and marks.
-    buffer.writeBytes(value, 0, value.readableBytes());
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = buffer.readSlice(currentSize);
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return "org.jboss.netty.buffer.ChannelBuffer";
-  }
-
-  @Override
-  public String toString() {
-    return "ChannelBufferField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    ChannelBufferField other = (ChannelBufferField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!value.equals(other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/DoubleArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/DoubleArrayField.java
deleted file mode 100644
index a0c3945f0dc4e1b7d29a3c50a7ce979e524f5112..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/DoubleArrayField.java
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class DoubleArrayField extends Field {
-
-  private final int size;
-
-  private double[] value;
-
-  public static DoubleArrayField newVariable(String name, int size) {
-    return new DoubleArrayField(PrimitiveFieldType.FLOAT64, name, size);
-  }
-
-  private DoubleArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new double[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public double[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((double[]) value).length == size);
-    this.value = (double[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (double v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new double[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readDouble();
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "DoubleArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    DoubleArrayField other = (DoubleArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/Field.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/Field.java
deleted file mode 100644
index d714dfc2d6a2a56e4021d12a06e104ecdc439c01..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/Field.java
+++ /dev/null
@@ -1,113 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public abstract class Field {
-
-  protected final FieldType type;
-  protected final String name;
-  protected final boolean isConstant;
-
-  protected Field(FieldType type, String name, boolean isConstant) {
-    this.name = name;
-    this.type = type;
-    this.isConstant = isConstant;
-  }
-
-  /**
-   * @return the name
-   */
-  public String getName() {
-    return name;
-  }
-
-  /**
-   * @return the type
-   */
-  public FieldType getType() {
-    return type;
-  }
-
-  /**
-   * @return <code>true</code> if this {@link ListField} represents a constant
-   */
-  public boolean isConstant() {
-    return isConstant;
-  }
-
-  /**
-   * @return the textual representation of this field used for computing the MD5
-   *         of a message definition
-   */
-  public String getMd5String() {
-    if (isConstant()) {
-      return String.format("%s %s=%s\n", getType().getMd5String(), getName(), getValue());
-    }
-    return String.format("%s %s\n", getType().getMd5String(), getName());
-  }
-
-  public abstract void serialize(ChannelBuffer buffer);
-
-  public abstract void deserialize(ChannelBuffer buffer);
-
-  public abstract <T> T getValue();
-
-  // TODO(damonkohler): Why not make Field generic?
-  public abstract void setValue(Object value);
-
-  public abstract String getJavaTypeName();
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + (isConstant ? 1231 : 1237);
-    result = prime * result + ((name == null) ? 0 : name.hashCode());
-    result = prime * result + ((type == null) ? 0 : type.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    Field other = (Field) obj;
-    if (isConstant != other.isConstant)
-      return false;
-    if (name == null) {
-      if (other.name != null)
-        return false;
-    } else if (!name.equals(other.name))
-      return false;
-    if (type == null) {
-      if (other.type != null)
-        return false;
-    } else if (!type.equals(other.type))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FieldFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FieldFactory.java
deleted file mode 100644
index 24b305397ca29bb898d53e14337beaf2a5dd171c..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FieldFactory.java
+++ /dev/null
@@ -1,25 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface FieldFactory {
-
-  Field create();
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FieldType.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FieldType.java
deleted file mode 100644
index b227b4db48fbba00635879e292cfd3f64d5d965b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FieldType.java
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface FieldType {
-
-  public <T> T getDefaultValue();
-
-  public String getName();
-
-  public <T> T parseFromString(String value);
-
-  public String getMd5String();
-
-  public String getJavaTypeName();
-
-  /**
-   * @return the serialized size of this {@link FieldType} in bytes
-   */
-  public int getSerializedSize();
-
-  public <T> void serialize(T value, ChannelBuffer buffer);
-
-  public <T> T deserialize(ChannelBuffer buffer);
-
-  public Field newVariableValue(String name);
-
-  public Field newVariableList(String name, int size);
-
-  public <T> Field newConstantValue(String name, T value);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FloatArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FloatArrayField.java
deleted file mode 100644
index fcbf50c29787df091a5a431a5e3f48fdc9c8be73..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/FloatArrayField.java
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class FloatArrayField extends Field {
-
-  private final int size;
-
-  private float[] value;
-
-  public static FloatArrayField newVariable(String name, int size) {
-    return new FloatArrayField(PrimitiveFieldType.FLOAT32, name, size);
-  }
-
-  private FloatArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new float[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public float[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((float[]) value).length == size);
-    this.value = (float[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (float v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new float[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readFloat();
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "FloatArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    FloatArrayField other = (FloatArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/IntegerArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/IntegerArrayField.java
deleted file mode 100644
index adb0753f44f8fb2e81e51ffabd46ce62fe702a27..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/IntegerArrayField.java
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class IntegerArrayField extends Field {
-
-  private final int size;
-
-  private int[] value;
-
-  public static IntegerArrayField newVariable(FieldType type, String name, int size) {
-    return new IntegerArrayField(type, name, size);
-  }
-
-  private IntegerArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new int[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public int[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((int[]) value).length == size);
-    this.value = (int[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (int v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new int[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readInt();
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "IntegerArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    IntegerArrayField other = (IntegerArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ListField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ListField.java
deleted file mode 100644
index 4f4caeb1e24120d4bbfc30cb26a459d12c630ae1..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ListField.java
+++ /dev/null
@@ -1,115 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.ArrayList;
-import java.util.List;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- * 
- * @param <T>
- *          the value type
- */
-public class ListField<T> extends Field {
-
-  private List<T> value;
-
-  public static <T> ListField<T> newVariable(FieldType type, String name) {
-    return new ListField<T>(type, name);
-  }
-
-  private ListField(FieldType type, String name) {
-    super(type, name, false);
-    value = new ArrayList<T>();
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public List<T> getValue() {
-    return value;
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkNotNull(value);
-    this.value = (List<T>) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    buffer.writeInt(value.size());
-    for (T v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    value.clear();
-    int size = buffer.readInt();
-    for (int i = 0; i < size; i++) {
-      value.add(type.<T>deserialize(buffer));
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return String.format("java.util.List<%s>", type.getJavaTypeName());
-  }
-
-  @Override
-  public String toString() {
-    return "ListField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @SuppressWarnings("rawtypes")
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    ListField other = (ListField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!value.equals(other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/LongArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/LongArrayField.java
deleted file mode 100644
index 8c2a611b24f4425517c70f27c92bd8dac4dd45f2..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/LongArrayField.java
+++ /dev/null
@@ -1,119 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class LongArrayField extends Field {
-
-  private final int size;
-
-  private long[] value;
-
-  public static LongArrayField newVariable(FieldType type, String name, int size) {
-    Preconditions.checkArgument(type.equals(PrimitiveFieldType.UINT32)
-        || type.equals(PrimitiveFieldType.INT64) || type.equals(PrimitiveFieldType.UINT64));
-    return new LongArrayField(type, name, size);
-  }
-
-  private LongArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new long[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public long[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((long[]) value).length == size);
-    this.value = (long[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (long v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new long[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readLong();
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "LongArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    LongArrayField other = (LongArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/MessageFieldType.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/MessageFieldType.java
deleted file mode 100644
index b70e6faf06eed79be3e23f248a6a232e1e1f877d..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/MessageFieldType.java
+++ /dev/null
@@ -1,136 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.internal.message.DefaultMessageDeserializer;
-import org.ros.internal.message.DefaultMessageSerializer;
-import org.ros.internal.message.Message;
-import org.ros.message.MessageDeserializer;
-import org.ros.message.MessageFactory;
-import org.ros.message.MessageIdentifier;
-import org.ros.message.MessageSerializer;
-
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageFieldType implements FieldType {
-
-  private final MessageIdentifier messageIdentifier;
-  private final MessageFactory messageFactory;
-  private final MessageSerializer<Message> serializer;
-  private final MessageDeserializer<Message> deserializer;
-
-  public MessageFieldType(MessageIdentifier messageIdentifier, MessageFactory messageFactory) {
-    this.messageIdentifier = messageIdentifier;
-    this.messageFactory = messageFactory;
-    serializer = new DefaultMessageSerializer();
-    deserializer = new DefaultMessageDeserializer<Message>(messageIdentifier, messageFactory);
-  }
-
-  public MessageFactory getMessageFactory() {
-    return messageFactory;
-  }
-
-  @Override
-  public Field newVariableValue(String name) {
-    return ValueField.newVariable(this, name);
-  }
-
-  @Override
-  public <T> Field newConstantValue(String name, T value) {
-    throw new UnsupportedOperationException();
-  }
-
-  @Override
-  public Field newVariableList(String name, int size) {
-    return ListField.newVariable(this, name);
-  }
-
-  @Override
-  public <T> T getDefaultValue() {
-    return getMessageFactory().newFromType(messageIdentifier.getType());
-  }
-
-  @Override
-  public String getMd5String() {
-    return null;
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return String.format("%s.%s", messageIdentifier.getPackage(), messageIdentifier.getName());
-  }
-
-  @Override
-  public int getSerializedSize() {
-    throw new UnsupportedOperationException();
-  }
-
-  @Override
-  public String getName() {
-    return messageIdentifier.getType();
-  }
-
-  @Override
-  public <T> void serialize(T value, ChannelBuffer buffer) {
-    serializer.serialize((Message) value, buffer);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public Message deserialize(ChannelBuffer buffer) {
-    return deserializer.deserialize(buffer);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public Void parseFromString(String value) {
-    throw new UnsupportedOperationException();
-  }
-
-  @Override
-  public String toString() {
-    return "MessageField<" + messageIdentifier + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + ((messageIdentifier == null) ? 0 : messageIdentifier.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    MessageFieldType other = (MessageFieldType) obj;
-    if (messageIdentifier == null) {
-      if (other.messageIdentifier != null)
-        return false;
-    } else if (!messageIdentifier.equals(other.messageIdentifier))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/MessageFields.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/MessageFields.java
deleted file mode 100644
index b640972d8150835733f373b530a6940d2f980a3e..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/MessageFields.java
+++ /dev/null
@@ -1,116 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.collect.Lists;
-import com.google.common.collect.Maps;
-
-import org.ros.exception.RosRuntimeException;
-import org.ros.internal.message.context.MessageContext;
-
-import java.util.Collections;
-import java.util.List;
-import java.util.Map;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageFields {
-
-  private final Map<String, Field> fields;
-  private final Map<String, Field> setters;
-  private final Map<String, Field> getters;
-  private final List<Field> orderedFields;
-
-  public MessageFields(MessageContext messageContext) {
-    fields = Maps.newHashMap();
-    setters = Maps.newHashMap();
-    getters = Maps.newHashMap();
-    orderedFields = Lists.newArrayList();
-    for (String name : messageContext.getFieldNames()) {
-      Field field = messageContext.getFieldFactory(name).create();
-      fields.put(name, field);
-      getters.put(messageContext.getFieldGetterName(name), field);
-      setters.put(messageContext.getFieldSetterName(name), field);
-      orderedFields.add(field);
-    }
-  }
-
-  public Field getField(String name) {
-    return fields.get(name);
-  }
-
-  public Field getSetterField(String name) {
-    return setters.get(name);
-  }
-
-  public Field getGetterField(String name) {
-    return getters.get(name);
-  }
-
-  public List<Field> getFields() {
-    return Collections.unmodifiableList(orderedFields);
-  }
-
-  public Object getFieldValue(String name) {
-    Field field = fields.get(name);
-    if (field != null) {
-      return field.getValue();
-    }
-    throw new RosRuntimeException("Uknown field: " + name);
-  }
-
-  public void setFieldValue(String name, Object value) {
-    Field field = fields.get(name);
-    if (field != null) {
-      field.setValue(value);
-    } else {
-      throw new RosRuntimeException("Uknown field: " + name);
-    }
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + ((fields == null) ? 0 : fields.hashCode());
-    result = prime * result + ((orderedFields == null) ? 0 : orderedFields.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    MessageFields other = (MessageFields) obj;
-    if (fields == null) {
-      if (other.fields != null)
-        return false;
-    } else if (!fields.equals(other.fields))
-      return false;
-    if (orderedFields == null) {
-      if (other.orderedFields != null)
-        return false;
-    } else if (!orderedFields.equals(other.orderedFields))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/PrimitiveFieldType.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/PrimitiveFieldType.java
deleted file mode 100644
index bed4916e876593fcb55c39af5348bb624423ca72..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/PrimitiveFieldType.java
+++ /dev/null
@@ -1,714 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-import com.google.common.collect.ImmutableSet;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-import org.ros.message.Duration;
-import org.ros.message.Time;
-
-import java.nio.ByteBuffer;
-import java.nio.charset.Charset;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public enum PrimitiveFieldType implements FieldType {
-
-  BOOL {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Boolean getDefaultValue() {
-      return Boolean.FALSE;
-    }
-
-    @Override
-    public BooleanArrayField newVariableList(String name, int size) {
-      return BooleanArrayField.newVariable(name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 1;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Boolean);
-      buffer.writeByte((byte) ((Boolean) value ? 1 : 0));
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Boolean deserialize(ChannelBuffer buffer) {
-      return buffer.readByte() == 1;
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Boolean parseFromString(String value) {
-      return value.equals("1");
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "boolean";
-    }
-  },
-  INT8 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte getDefaultValue() {
-      return Byte.valueOf((byte) 0);
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ChannelBufferField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 1;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Byte);
-      buffer.writeByte((Byte) value);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte deserialize(ChannelBuffer buffer) {
-      return buffer.readByte();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte parseFromString(String value) {
-      return Byte.parseByte(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "byte";
-    }
-  },
-  /**
-   * @deprecated replaced by {@link PrimitiveFieldType#INT8}
-   */
-  BYTE {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte getDefaultValue() {
-      return INT8.getDefaultValue();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ChannelBufferField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return INT8.getSerializedSize();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      INT8.serialize(value, buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte deserialize(ChannelBuffer buffer) {
-      return INT8.deserialize(buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte parseFromString(String value) {
-      return INT8.parseFromString(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return INT8.getJavaTypeName();
-    }
-  },
-  UINT8 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte getDefaultValue() {
-      return INT8.getDefaultValue();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ChannelBufferField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return INT8.getSerializedSize();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      INT8.serialize(value, buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte deserialize(ChannelBuffer buffer) {
-      return INT8.deserialize(buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte parseFromString(String value) {
-      return (byte) Short.parseShort(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return INT8.getJavaTypeName();
-    }
-  },
-  /**
-   * @deprecated replaced by {@link PrimitiveFieldType#UINT8}
-   */
-  CHAR {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte getDefaultValue() {
-      return UINT8.getDefaultValue();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ChannelBufferField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return UINT8.getSerializedSize();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      UINT8.serialize(value, buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte deserialize(ChannelBuffer buffer) {
-      return UINT8.deserialize(buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Byte parseFromString(String value) {
-      return UINT8.parseFromString(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return UINT8.getJavaTypeName();
-    }
-  },
-  INT16 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Short getDefaultValue() {
-      return Short.valueOf((short) 0);
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ShortArrayField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 2;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Short);
-      buffer.writeShort((Short) value);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Short deserialize(ChannelBuffer buffer) {
-      return buffer.readShort();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Short parseFromString(String value) {
-      return Short.parseShort(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "short";
-    }
-  },
-  UINT16 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Short getDefaultValue() {
-      return INT16.getDefaultValue();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ShortArrayField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return INT16.getSerializedSize();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      INT16.serialize(value, buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Short deserialize(ChannelBuffer buffer) {
-      return INT16.deserialize(buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Short parseFromString(String value) {
-      return (short) Integer.parseInt(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return INT16.getJavaTypeName();
-    }
-  },
-  INT32 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Integer getDefaultValue() {
-      return Integer.valueOf(0);
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return IntegerArrayField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 4;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Integer);
-      buffer.writeInt((Integer) value);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Integer deserialize(ChannelBuffer buffer) {
-      return buffer.readInt();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Integer parseFromString(String value) {
-      return Integer.parseInt(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "int";
-    }
-  },
-  UINT32 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Integer getDefaultValue() {
-      return INT32.getDefaultValue();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return IntegerArrayField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return INT32.getSerializedSize();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      INT32.serialize(value, buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Integer deserialize(ChannelBuffer buffer) {
-      return INT32.deserialize(buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Integer parseFromString(String value) {
-      return (int) Long.parseLong(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return INT32.getJavaTypeName();
-    }
-  },
-  INT64 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Long getDefaultValue() {
-      return Long.valueOf(0);
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return LongArrayField.newVariable(this, name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 8;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Long);
-      buffer.writeLong((Long) value);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Long deserialize(ChannelBuffer buffer) {
-      return buffer.readLong();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Long parseFromString(String value) {
-      return Long.parseLong(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "long";
-    }
-  },
-  UINT64 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Long getDefaultValue() {
-      return INT64.getDefaultValue();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return INT64.newVariableList(name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return INT64.getSerializedSize();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      INT64.serialize(value, buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Long deserialize(ChannelBuffer buffer) {
-      return INT64.deserialize(buffer);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Long parseFromString(String value) {
-      return INT64.parseFromString(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return INT64.getJavaTypeName();
-    }
-  },
-  FLOAT32 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Float getDefaultValue() {
-      return Float.valueOf(0);
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return FloatArrayField.newVariable(name, size);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 4;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Float);
-      buffer.writeFloat((Float) value);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Float deserialize(ChannelBuffer buffer) {
-      return buffer.readFloat();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Float parseFromString(String value) {
-      return Float.parseFloat(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "float";
-    }
-  },
-  FLOAT64 {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Double getDefaultValue() {
-      return Double.valueOf(0);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 8;
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return DoubleArrayField.newVariable(name, size);
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Double);
-      buffer.writeDouble((Double) value);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Double deserialize(ChannelBuffer buffer) {
-      return buffer.readDouble();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Double parseFromString(String value) {
-      return Double.parseDouble(value);
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "double";
-    }
-  },
-  STRING {
-    @SuppressWarnings("unchecked")
-    @Override
-    public String getDefaultValue() {
-      return "";
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ListField.newVariable(this, name);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      throw new UnsupportedOperationException();
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof String);
-      byte[] bytes = ((String) value).getBytes();
-      buffer.writeInt(bytes.length);
-      buffer.writeBytes(bytes);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public String deserialize(ChannelBuffer buffer) {
-      int length = buffer.readInt();
-      ByteBuffer stringBuffer = buffer.readSlice(length).toByteBuffer();
-      return Charset.forName("US-ASCII").decode(stringBuffer).toString();
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public String parseFromString(String value) {
-      return value;
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return "java.lang.String";
-    }
-  },
-  TIME {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Time getDefaultValue() {
-      return new Time();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ListField.newVariable(this, name);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 8;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Time);
-      buffer.writeInt(((Time) value).secs);
-      buffer.writeInt(((Time) value).nsecs);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Time deserialize(ChannelBuffer buffer) {
-      return new Time(buffer.readInt(), buffer.readInt());
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Void parseFromString(String value) {
-      throw new UnsupportedOperationException();
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return Time.class.getName();
-    }
-  },
-  DURATION {
-    @SuppressWarnings("unchecked")
-    @Override
-    public Duration getDefaultValue() {
-      return new Duration();
-    }
-
-    @Override
-    public Field newVariableList(String name, int size) {
-      return ListField.newVariable(this, name);
-    }
-
-    @Override
-    public int getSerializedSize() {
-      return 8;
-    }
-
-    @Override
-    public <T> void serialize(T value, ChannelBuffer buffer) {
-      Preconditions.checkArgument(value instanceof Duration);
-      buffer.writeInt(((Duration) value).secs);
-      buffer.writeInt(((Duration) value).nsecs);
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Duration deserialize(ChannelBuffer buffer) {
-      return new Duration(buffer.readInt(), buffer.readInt());
-    }
-
-    @SuppressWarnings("unchecked")
-    @Override
-    public Void parseFromString(String value) {
-      throw new UnsupportedOperationException();
-    }
-
-    @Override
-    public String getJavaTypeName() {
-      return Duration.class.getName();
-    }
-  };
-
-  private static final ImmutableSet<String> TYPE_NAMES;
-
-  static {
-    ImmutableSet.Builder<String> builder = ImmutableSet.<String>builder();
-    for (PrimitiveFieldType type : values()) {
-      builder.add(type.getName());
-    }
-    TYPE_NAMES = builder.build();
-  }
-
-  public static boolean existsFor(String name) {
-    return TYPE_NAMES.contains(name);
-  }
-
-  @Override
-  public Field newVariableValue(String name) {
-    return ValueField.newVariable(this, name);
-  }
-
-  @Override
-  public <T> Field newConstantValue(String name, T value) {
-    return ValueField.newConstant(this, name, value);
-  }
-
-  @Override
-  public String getName() {
-    return toString().toLowerCase();
-  }
-
-  @Override
-  public String getMd5String() {
-    return getName();
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ShortArrayField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ShortArrayField.java
deleted file mode 100644
index e77b72a34e00eb4c188dcd0cb799b09a205dcb93..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ShortArrayField.java
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-import java.util.Arrays;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ShortArrayField extends Field {
-
-  private final int size;
-
-  private short[] value;
-
-  public static ShortArrayField newVariable(FieldType type, String name, int size) {
-    return new ShortArrayField(type, name, size);
-  }
-
-  private ShortArrayField(FieldType type, String name, int size) {
-    super(type, name, false);
-    this.size = size;
-    setValue(new short[Math.max(0, size)]);
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public short[] getValue() {
-    return value;
-  }
-
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkArgument(size < 0 || ((short[]) value).length == size);
-    this.value = (short[]) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    if (size < 0) {
-      buffer.writeInt(value.length);
-    }
-    for (short v : value) {
-      type.serialize(v, buffer);
-    }
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    int currentSize = size;
-    if (currentSize < 0) {
-      currentSize = buffer.readInt();
-    }
-    value = new short[currentSize];
-    for (int i = 0; i < currentSize; i++) {
-      value[i] = buffer.readShort();
-    }
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName() + "[]";
-  }
-
-  @Override
-  public String toString() {
-    return "ShortArrayField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((value == null) ? 0 : value.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    ShortArrayField other = (ShortArrayField) obj;
-    if (value == null) {
-      if (other.value != null)
-        return false;
-    } else if (!Arrays.equals(value, other.value))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ValueField.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ValueField.java
deleted file mode 100644
index d2baacf59bbddc11860ec0f110fc56c9d0a60dce..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/field/ValueField.java
+++ /dev/null
@@ -1,110 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.field;
-
-import com.google.common.base.Preconditions;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-class ValueField<T> extends Field {
-
-  private T value;
-
-  static <T> ValueField<T> newConstant(FieldType type, String name, T value) {
-    return new ValueField<T>(type, name, value, true);
-  }
-
-  static <T> ValueField<T> newVariable(FieldType type, String name) {
-    return new ValueField<T>(type, name, null, false);
-  }
-
-  private ValueField(FieldType type, String name, T value, boolean isConstant) {
-    super(type, name, isConstant);
-    this.value = value;
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public T getValue() {
-    if (value == null) {
-      setValue(type.getDefaultValue());
-    }
-    return value;
-  }
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public void setValue(Object value) {
-    Preconditions.checkNotNull(value);
-    Preconditions.checkState(!isConstant);
-    this.value = (T) value;
-  }
-
-  @Override
-  public void serialize(ChannelBuffer buffer) {
-    type.serialize(getValue(), buffer);
-  }
-
-  @Override
-  public void deserialize(ChannelBuffer buffer) {
-    Preconditions.checkState(!isConstant);
-    setValue(type.<T>deserialize(buffer));
-  }
-
-  @Override
-  public String getMd5String() {
-    return String.format("%s %s\n", type, name);
-  }
-
-  @Override
-  public String getJavaTypeName() {
-    return type.getJavaTypeName();
-  }
-
-  @Override
-  public String toString() {
-    return "ValueField<" + type + ", " + name + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((getValue() == null) ? 0 : getValue().hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    Field other = (Field) obj;
-    if (getValue() == null) {
-      if (other.getValue() != null)
-        return false;
-    } else if (!getValue().equals(other.getValue()))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/package-info.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/package-info.java
deleted file mode 100644
index a59b1c8e6a88cb4e9fe6cf85c7f1104ac2b01043..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/package-info.java
+++ /dev/null
@@ -1,22 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-/**
- * Provides internal classes for representing messages.
- * <p>
- * These classes should _not_ be used directly outside of the org.ros package.
- */
-package org.ros.internal.message;
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDefinitionFileProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDefinitionFileProvider.java
deleted file mode 100644
index 31b258f897ac6f5d85699739340638ea4ade61f6..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDefinitionFileProvider.java
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.definition.MessageDefinitionFileProvider;
-
-import org.apache.commons.io.filefilter.FileFilterUtils;
-import org.apache.commons.io.filefilter.IOFileFilter;
-import org.ros.internal.message.StringFileProvider;
-
-import java.io.File;
-import java.io.FileFilter;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceDefinitionFileProvider extends MessageDefinitionFileProvider {
-
-  private static final String PARENT = "srv";
-  private static final String SUFFIX = "srv";
-
-  private static StringFileProvider newStringFileProvider() {
-    IOFileFilter extensionFilter = FileFilterUtils.suffixFileFilter(SUFFIX);
-    IOFileFilter parentBaseNameFilter = FileFilterUtils.asFileFilter(new FileFilter() {
-      @Override
-      public boolean accept(File file) {
-        return getParentBaseName(file.getAbsolutePath()).equals(PARENT);
-      }
-    });
-    IOFileFilter fileFilter = FileFilterUtils.andFileFilter(extensionFilter, parentBaseNameFilter);
-    return new StringFileProvider(fileFilter);
-  }
-
-  public ServiceDefinitionFileProvider() {
-    super(newStringFileProvider());
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDefinitionResourceProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDefinitionResourceProvider.java
deleted file mode 100644
index af35e3ff748ecd21d0215a0be2dfa5f9706bdf93..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDefinitionResourceProvider.java
+++ /dev/null
@@ -1,69 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import com.google.common.base.Preconditions;
-
-import org.ros.internal.message.StringResourceProvider;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageIdentifier;
-
-import java.util.Collection;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceDefinitionResourceProvider implements MessageDefinitionProvider {
-
-  private final StringResourceProvider stringResourceProvider;
-
-  public ServiceDefinitionResourceProvider() {
-    stringResourceProvider = new StringResourceProvider();
-  }
-
-  private String serviceTypeToResourceName(String serviceType) {
-    Preconditions.checkArgument(serviceType.contains("/"), "Service type must be fully qualified: "
-        + serviceType);
-    String[] packageAndType = serviceType.split("/", 2);
-    return String.format("/%s/srv/%s.srv", packageAndType[0], packageAndType[1]);
-  }
-
-  @Override
-  public String get(String serviceType) {
-    return stringResourceProvider.get(serviceTypeToResourceName(serviceType));
-  }
-
-  @Override
-  public boolean has(String serviceType) {
-    return stringResourceProvider.has(serviceTypeToResourceName(serviceType));
-  }
-
-  public void add(String serviceType, String serviceDefinition) {
-    stringResourceProvider.addStringToCache(serviceTypeToResourceName(serviceType),
-        serviceDefinition);
-  }
-
-  @Override
-  public Collection<String> getPackages() {
-    throw new UnsupportedOperationException();
-  }
-
-  @Override
-  public Collection<MessageIdentifier> getMessageIdentifiersByPackage(String pkg) {
-    throw new UnsupportedOperationException();
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDescription.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDescription.java
deleted file mode 100644
index 95251a0422a9f4786ce3ac9cabfd353afefd3a9d..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDescription.java
+++ /dev/null
@@ -1,98 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.definition.MessageDefinitionTupleParser;
-
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageIdentifier;
-
-import java.util.List;
-
-/**
- * The description of a ROS service.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceDescription extends MessageDeclaration {
-
-  private final String requestType;
-  private final String requestDefinition;
-  private final String responseType;
-  private final String responseDefinition;
-  private final String md5Checksum;
-
-  public ServiceDescription(String type, String definition, String md5Checksum) {
-    super(MessageIdentifier.of(type), definition);
-    this.md5Checksum = md5Checksum;
-    List<String> requestAndResponse = MessageDefinitionTupleParser.parse(definition, 2);
-    requestType = type + "Request";
-    responseType = type + "Response";
-    requestDefinition = requestAndResponse.get(0);
-    responseDefinition = requestAndResponse.get(1);
-  }
-
-  public String getMd5Checksum() {
-    return md5Checksum;
-  }
-
-  public String getRequestType() {
-    return requestType;
-  }
-
-  public String getRequestDefinition() {
-    return requestDefinition;
-  }
-
-  public String getResponseType() {
-    return responseType;
-  }
-
-  public String getResponseDefinition() {
-    return responseDefinition;
-  }
-
-  @Override
-  public String toString() {
-    return "ServiceDescription<" + getType() + ", " + md5Checksum + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((md5Checksum == null) ? 0 : md5Checksum.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    ServiceDescription other = (ServiceDescription) obj;
-    if (md5Checksum == null) {
-      if (other.md5Checksum != null)
-        return false;
-    } else if (!md5Checksum.equals(other.md5Checksum))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDescriptionFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDescriptionFactory.java
deleted file mode 100644
index 269d4024d306bbce3707025e8e2131c53ed63cd4..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceDescriptionFactory.java
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.Md5Generator;
-import org.ros.message.MessageDefinitionProvider;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceDescriptionFactory {
-
-  private final MessageDefinitionProvider messageDefinitionProvider;
-  private final Md5Generator md5Generator;
-
-  public ServiceDescriptionFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    this.messageDefinitionProvider = messageDefinitionProvider;
-    md5Generator = new Md5Generator(messageDefinitionProvider);
-  }
-
-  public ServiceDescription newFromType(String serviceType) {
-    String serviceDefinition = messageDefinitionProvider.get(serviceType);
-    String md5Checksum = md5Generator.generate(serviceType);
-    return new ServiceDescription(serviceType, serviceDefinition, md5Checksum);
-  }
-
-  public boolean hasType(String serviceType) {
-    return messageDefinitionProvider.has(serviceType);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceRequestMessageFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceRequestMessageFactory.java
deleted file mode 100644
index 862b20d132a38adfc6b6d4782f5c85c8d570ff87..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceRequestMessageFactory.java
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.DefaultMessageFactory;
-import org.ros.internal.message.DefaultMessageInterfaceClassProvider;
-import org.ros.internal.message.MessageProxyFactory;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageFactory;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceRequestMessageFactory implements MessageFactory {
-
-  private final ServiceDescriptionFactory serviceDescriptionFactory;
-  private final MessageFactory messageFactory;
-  private final MessageProxyFactory messageProxyFactory;
-
-  public ServiceRequestMessageFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    serviceDescriptionFactory = new ServiceDescriptionFactory(messageDefinitionProvider);
-    messageFactory = new DefaultMessageFactory(messageDefinitionProvider);
-    messageProxyFactory =
-        new MessageProxyFactory(new DefaultMessageInterfaceClassProvider(), messageFactory);
-  }
-
-  @Override
-  public <T> T newFromType(String serviceType) {
-    ServiceDescription serviceDescription = serviceDescriptionFactory.newFromType(serviceType);
-    MessageDeclaration messageDeclaration =
-        MessageDeclaration.of(serviceDescription.getRequestType(),
-            serviceDescription.getRequestDefinition());
-    return messageProxyFactory.newMessageProxy(messageDeclaration);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceRequestMessageInterfaceClassProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceRequestMessageInterfaceClassProvider.java
deleted file mode 100644
index 24b4b52f0832903ec363e5a8b3d8bd844b129d20..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceRequestMessageInterfaceClassProvider.java
+++ /dev/null
@@ -1,37 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.MessageInterfaceClassProvider;
-import org.ros.internal.message.RawMessage;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceRequestMessageInterfaceClassProvider implements MessageInterfaceClassProvider {
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public <T> Class<T> get(String messageType) {
-    try {
-      String className = messageType.replace("/", ".") + "$Request";
-      return (Class<T>) getClass().getClassLoader().loadClass(className);
-    } catch (ClassNotFoundException e) {
-      return (Class<T>) RawMessage.class;
-    }
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceResponseMessageFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceResponseMessageFactory.java
deleted file mode 100644
index c325c44bbb897ec9bd54a7c2a5a2075441029bcb..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceResponseMessageFactory.java
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.DefaultMessageFactory;
-import org.ros.internal.message.DefaultMessageInterfaceClassProvider;
-import org.ros.internal.message.MessageProxyFactory;
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageFactory;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceResponseMessageFactory implements MessageFactory {
-
-  private final ServiceDescriptionFactory serviceDescriptionFactory;
-  private final MessageFactory messageFactory;
-  private final MessageProxyFactory messageProxyFactory;
-
-  public ServiceResponseMessageFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    serviceDescriptionFactory = new ServiceDescriptionFactory(messageDefinitionProvider);
-    messageFactory = new DefaultMessageFactory(messageDefinitionProvider);
-    messageProxyFactory =
-        new MessageProxyFactory(new DefaultMessageInterfaceClassProvider(), messageFactory);
-  }
-
-  @Override
-  public <T> T newFromType(String serviceType) {
-    ServiceDescription serviceDescription = serviceDescriptionFactory.newFromType(serviceType);
-    MessageDeclaration messageDeclaration =
-        MessageDeclaration.of(serviceDescription.getResponseType(),
-            serviceDescription.getResponseDefinition());
-    return messageProxyFactory.newMessageProxy(messageDeclaration);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceResponseMessageInterfaceClassProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceResponseMessageInterfaceClassProvider.java
deleted file mode 100644
index 0e61fb93504788b14df69f0ac71616b9d82f5b78..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/ServiceResponseMessageInterfaceClassProvider.java
+++ /dev/null
@@ -1,37 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.service;
-
-import org.ros.internal.message.MessageInterfaceClassProvider;
-import org.ros.internal.message.RawMessage;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class ServiceResponseMessageInterfaceClassProvider implements MessageInterfaceClassProvider {
-
-  @SuppressWarnings("unchecked")
-  @Override
-  public <T> Class<T> get(String messageType) {
-    try {
-      String className = messageType.replace("/", ".") + "$Response";
-      return (Class<T>) getClass().getClassLoader().loadClass(className);
-    } catch (ClassNotFoundException e) {
-      return (Class<T>) RawMessage.class;
-    }
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/package-info.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/package-info.java
deleted file mode 100644
index 82c803803734999f12bc13a6dfa9b286303ecd89..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/service/package-info.java
+++ /dev/null
@@ -1,22 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-/**
- * Provides internal classes for representing service messages.
- * <p>
- * These classes should _not_ be used directly outside of the org.ros package.
- */
-package org.ros.internal.message.service;
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDefinitionFileProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDefinitionFileProvider.java
deleted file mode 100644
index 5cc8e1efb3b52bf9a6e3d368aa9a6597d5eccfb7..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDefinitionFileProvider.java
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.topic;
-
-import org.ros.internal.message.definition.MessageDefinitionFileProvider;
-
-import org.apache.commons.io.filefilter.FileFilterUtils;
-import org.apache.commons.io.filefilter.IOFileFilter;
-import org.ros.internal.message.StringFileProvider;
-
-import java.io.File;
-import java.io.FileFilter;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class TopicDefinitionFileProvider extends MessageDefinitionFileProvider {
-
-  private static final String PARENT = "msg";
-  private static final String SUFFIX = "msg";
-
-  private static StringFileProvider newStringFileProvider() {
-    IOFileFilter extensionFilter = FileFilterUtils.suffixFileFilter(SUFFIX);
-    IOFileFilter parentBaseNameFilter = FileFilterUtils.asFileFilter(new FileFilter() {
-      @Override
-      public boolean accept(File file) {
-        return getParentBaseName(file.getAbsolutePath()).equals(PARENT);
-      }
-    });
-    IOFileFilter fileFilter = FileFilterUtils.andFileFilter(extensionFilter, parentBaseNameFilter);
-    return new StringFileProvider(fileFilter);
-  }
-
-  public TopicDefinitionFileProvider() {
-    super(newStringFileProvider());
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDefinitionResourceProvider.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDefinitionResourceProvider.java
deleted file mode 100644
index 08dce892ed8264f6c4b4d2b2cbadddf05a4d6c79..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDefinitionResourceProvider.java
+++ /dev/null
@@ -1,68 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.topic;
-
-import com.google.common.annotations.VisibleForTesting;
-
-import org.ros.internal.message.StringResourceProvider;
-import org.ros.message.MessageDefinitionProvider;
-import org.ros.message.MessageIdentifier;
-
-import java.util.Collection;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class TopicDefinitionResourceProvider implements MessageDefinitionProvider {
-
-  private final StringResourceProvider stringResourceProvider;
-
-  public TopicDefinitionResourceProvider() {
-    stringResourceProvider = new StringResourceProvider();
-  }
-
-  private String topicTypeToResourceName(String topicType) {
-    MessageIdentifier messageIdentifier = MessageIdentifier.of(topicType);
-    return String.format("/%s/msg/%s.msg", messageIdentifier.getPackage(),
-        messageIdentifier.getName());
-  }
-
-  @Override
-  public String get(String topicType) {
-    return stringResourceProvider.get(topicTypeToResourceName(topicType));
-  }
-
-  @Override
-  public boolean has(String topicType) {
-    return stringResourceProvider.has(topicTypeToResourceName(topicType));
-  }
-
-  @VisibleForTesting
-  public void add(String topicType, String topicDefinition) {
-    stringResourceProvider.addStringToCache(topicTypeToResourceName(topicType), topicDefinition);
-  }
-
-  @Override
-  public Collection<String> getPackages() {
-    throw new UnsupportedOperationException();
-  }
-
-  @Override
-  public Collection<MessageIdentifier> getMessageIdentifiersByPackage(String pkg) {
-    throw new UnsupportedOperationException();
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDescription.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDescription.java
deleted file mode 100644
index 50c9ad33f9a088824d5aa6bcf6dd1b93bd81b1dd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDescription.java
+++ /dev/null
@@ -1,69 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.topic;
-
-import org.ros.message.MessageDeclaration;
-import org.ros.message.MessageIdentifier;
-
-/**
- * The description of a ROS topic.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class TopicDescription extends MessageDeclaration {
-
-  private final String md5Checksum;
-
-  public TopicDescription(String type, String definition, String md5Checksum) {
-    super(MessageIdentifier.of(type), definition);
-    this.md5Checksum = md5Checksum;
-  }
-
-  public String getMd5Checksum() {
-    return md5Checksum;
-  }
-
-  @Override
-  public String toString() {
-    return "TopicDescription<" + getType() + ", " + md5Checksum + ">";
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = super.hashCode();
-    result = prime * result + ((md5Checksum == null) ? 0 : md5Checksum.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (!super.equals(obj))
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    TopicDescription other = (TopicDescription) obj;
-    if (md5Checksum == null) {
-      if (other.md5Checksum != null)
-        return false;
-    } else if (!md5Checksum.equals(other.md5Checksum))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDescriptionFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDescriptionFactory.java
deleted file mode 100644
index 27e8620dd40ccaac34dd948006d93d186c0b5b57..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicDescriptionFactory.java
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.topic;
-
-import org.ros.internal.message.Md5Generator;
-import org.ros.message.MessageDefinitionProvider;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class TopicDescriptionFactory {
-
-  private final MessageDefinitionProvider messageDefinitionProvider;
-  private final Md5Generator md5Generator;
-
-  public TopicDescriptionFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    this.messageDefinitionProvider = messageDefinitionProvider;
-    md5Generator = new Md5Generator(messageDefinitionProvider);
-  }
-
-  public TopicDescription newFromType(String topicType) {
-    String md5Checksum = md5Generator.generate(topicType);
-    String topicDefinition = messageDefinitionProvider.get(topicType);
-    return new TopicDescription(topicType, topicDefinition, md5Checksum);
-  }
-
-  public boolean hasType(String topicType) {
-    return messageDefinitionProvider.has(topicType);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicMessageFactory.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicMessageFactory.java
deleted file mode 100644
index b329386c751b1f48dee6f7eb90c8d02a5dfb835f..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/TopicMessageFactory.java
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.internal.message.topic;
-
-import org.ros.internal.message.DefaultMessageFactory;
-import org.ros.message.MessageDefinitionProvider;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class TopicMessageFactory extends DefaultMessageFactory {
-
-  public TopicMessageFactory(MessageDefinitionProvider messageDefinitionProvider) {
-    super(messageDefinitionProvider);
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/package-info.java b/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/package-info.java
deleted file mode 100644
index d270dee4ab685ddb5f150d9b619edd72a0fb80a7..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/internal/message/topic/package-info.java
+++ /dev/null
@@ -1,22 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-/**
- * Provides internal classes for representing topic messages.
- * <p>
- * These classes should _not_ be used directly outside of the org.ros package.
- */
-package org.ros.internal.message.topic;
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/Duration.java b/rosjava_bootstrap/src/main/java/org/ros/message/Duration.java
deleted file mode 100644
index d67c8c8627f2f0418de4a0fcc8c4f2a50eba606f..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/Duration.java
+++ /dev/null
@@ -1,167 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2008, Willow Garage, Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage, Inc. nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-package org.ros.message;
-
-/**
- * ROS Duration representation. Time and Duration are primitive types in ROS.
- * ROS represents each as two 32-bit integers: seconds and nanoseconds since
- * epoch.
- * 
- * http://www.ros.org/wiki/msg
- * 
- * @author Jason Wolfe
- * @author kwc@willowgarage.com (Ken Conley)
- * 
- */
-public class Duration implements Comparable<Duration> {
-
-  public static final Duration MAX_VALUE = new Duration(Integer.MAX_VALUE, 999999999);
-
-  public int secs;
-  public int nsecs;
-
-  public Duration() {
-  }
-
-  public Duration(int secs, int nsecs) {
-    this.secs = secs;
-    this.nsecs = nsecs;
-    normalize();
-  }
-
-  public Duration(double secs) {
-    this.secs = (int) secs;
-    this.nsecs = (int) ((secs - this.secs) * 1000000000);
-    normalize();
-  }
-
-  public Duration(Duration t) {
-    this.secs = t.secs;
-    this.nsecs = t.nsecs;
-  }
-
-  public Duration add(Duration d) {
-    return new Duration(secs + d.secs, nsecs + d.nsecs);
-  }
-
-  public Duration subtract(Duration d) {
-    return new Duration(secs - d.secs, nsecs - d.nsecs);
-  }
-
-  public static Duration fromMillis(long durationInMillis) {
-    int secs = (int) (durationInMillis / 1000);
-    int nsecs = (int) (durationInMillis % 1000) * 1000000;
-    return new Duration(secs, nsecs);
-  }
-
-  public static Duration fromNano(long durationInNs) {
-    int secs = (int) (durationInNs / 1000000000);
-    int nsecs = (int) (durationInNs % 1000000000);
-    return new Duration(secs, nsecs);
-  }
-
-  public void normalize() {
-    while (nsecs < 0) {
-      nsecs += 1000000000;
-      secs -= 1;
-    }
-    while (nsecs >= 1000000000) {
-      nsecs -= 1000000000;
-      secs += 1;
-    }
-  }
-
-  public long totalNsecs() {
-    return ((long) secs) * 1000000000 + nsecs;
-  }
-
-  public boolean isZero() {
-    return totalNsecs() == 0;
-  }
-
-  public boolean isPositive() {
-    return totalNsecs() > 0;
-  }
-
-  public boolean isNegative() {
-    return totalNsecs() < 0;
-  }
-
-  @Override
-  public String toString() {
-    return secs + ":" + nsecs;
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + nsecs;
-    result = prime * result + secs;
-    return result;
-  }
-
-  @Override
-  /**
-   * Check for equality between Time objects.  
-   * equals() does not normalize Time representations, so fields must match exactly.
-   */
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    Duration other = (Duration) obj;
-    if (nsecs != other.nsecs)
-      return false;
-    if (secs != other.secs)
-      return false;
-    return true;
-  }
-
-  @Override
-  public int compareTo(Duration d) {
-    if ((secs > d.secs) || ((secs == d.secs) && nsecs > d.nsecs)) {
-      return 1;
-    }
-    if ((secs == d.secs) && (nsecs == d.nsecs)) {
-      return 0;
-    }
-    return -1;
-  }
-
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageDeclaration.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageDeclaration.java
deleted file mode 100644
index 57a846e5198b660adb3ba2e3083dc4e520787eb1..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageDeclaration.java
+++ /dev/null
@@ -1,108 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-import com.google.common.base.Preconditions;
-
-/**
- * An {@link MessageIdentifier} and definition pair from which all qualities of
- * the message uniquely identifiable by the {@link MessageIdentifier} can be
- * derived.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageDeclaration {
-
-  private final MessageIdentifier messageIdentifier;
-  private final String definition;
-
-  public static MessageDeclaration of(String type, String definition) {
-    Preconditions.checkNotNull(type);
-    Preconditions.checkNotNull(definition);
-    return new MessageDeclaration(MessageIdentifier.of(type), definition);
-  }
-
-  /**
-   * @param messageIdentifier
-   *          the {@link MessageIdentifier}
-   * @param definition
-   *          the message definition
-   */
-  public MessageDeclaration(MessageIdentifier messageIdentifier, String definition) {
-    Preconditions.checkNotNull(messageIdentifier);
-    Preconditions.checkNotNull(definition);
-    this.messageIdentifier = messageIdentifier;
-    this.definition = definition;
-  }
-
-  public MessageIdentifier getMessageIdentifier() {
-    return messageIdentifier;
-  }
-
-  public String getType() {
-    return messageIdentifier.getType();
-  }
-
-  public String getPackage() {
-    return messageIdentifier.getPackage();
-  }
-
-  public String getName() {
-    return messageIdentifier.getName();
-  }
-
-  public String getDefinition() {
-    Preconditions.checkNotNull(definition);
-    return definition;
-  }
-
-  @Override
-  public String toString() {
-    return String.format("MessageDeclaration<%s>", messageIdentifier.toString());
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + ((definition == null) ? 0 : definition.hashCode());
-    result = prime * result + ((messageIdentifier == null) ? 0 : messageIdentifier.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    MessageDeclaration other = (MessageDeclaration) obj;
-    if (definition == null) {
-      if (other.definition != null)
-        return false;
-    } else if (!definition.equals(other.definition))
-      return false;
-    if (messageIdentifier == null) {
-      if (other.messageIdentifier != null)
-        return false;
-    } else if (!messageIdentifier.equals(other.messageIdentifier))
-      return false;
-    return true;
-  }
-}
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageDefinitionProvider.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageDefinitionProvider.java
deleted file mode 100644
index b62715c757d394fbdb7bf46f5ae0b1ea5df736b2..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageDefinitionProvider.java
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-import java.util.Collection;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface MessageDefinitionProvider {
-
-  /**
-   * @param messageType
-   *          the type of message definition to provide
-   * @return the message definition for the specified type
-   */
-  String get(String messageType);
-
-  /**
-   * @param messageType
-   *          the type of message definition to provide
-   * @return {@code true} if the definition for the specified type is available,
-   *         {@code false} otherwise
-   */
-  boolean has(String messageType);
-
-  Collection<String> getPackages();
-
-  /**
-   * @param pkg
-   *          the name of the package to filter on
-   * @return the {@link MessageIdentifier}s for all messages defined in the
-   *         specified package
-   */
-  Collection<MessageIdentifier> getMessageIdentifiersByPackage(String pkg);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageDeserializer.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageDeserializer.java
deleted file mode 100644
index 326c5101577036fb46a857fb35a95125e7e82d63..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageDeserializer.java
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- * 
- * @param <T>
- *          the type of message that this {@link MessageDeserializer} can
- *          deserialize
- */
-public interface MessageDeserializer<T> {
-  
-  T deserialize(ChannelBuffer buffer);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageFactory.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageFactory.java
deleted file mode 100644
index 9babe2f121c492948a6a6d8226641c39e98c8a2a..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageFactory.java
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface MessageFactory {
-
-  /**
-   * @param messageType
-   *          the type of message to create
-   * @return a new message
-   */
-  <T> T newFromType(String messageType);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageFactoryProvider.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageFactoryProvider.java
deleted file mode 100644
index 24e8713d428ec800d4dbede089c948a16560305b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageFactoryProvider.java
+++ /dev/null
@@ -1,24 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-public interface MessageFactoryProvider {
-
-  MessageFactory get(MessageIdentifier messageIdentifier);
-
-  boolean has(MessageIdentifier messageIdentifier);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageIdentifier.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageIdentifier.java
deleted file mode 100644
index 9895c39e41f1bd2eba9c904cce06a4aed2efadf8..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageIdentifier.java
+++ /dev/null
@@ -1,121 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-import com.google.common.base.Preconditions;
-
-/**
- * Uniquely identifies a message.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- */
-public class MessageIdentifier {
-
-  private String type;
-  private String pkg;
-  private String name;
-
-  public static MessageIdentifier of(String pkg, String name) {
-    Preconditions.checkNotNull(pkg);
-    Preconditions.checkNotNull(name);
-    return new MessageIdentifier(pkg, name);
-  }
-
-  public static MessageIdentifier of(String type) {
-    Preconditions.checkNotNull(type);
-    // We're not using Preconditions.checkArgument() here because we want a
-    // useful error message without paying the performance penalty of
-    // constructing it every time.
-    if (!type.contains("/")) {
-      throw new IllegalArgumentException(String.format(
-          "Type name is invalid or not fully qualified: \"%s\"", type));
-    }
-    return new MessageIdentifier(type);
-  }
-
-  private MessageIdentifier(String type) {
-    this.type = type;
-  }
-
-  private MessageIdentifier(String pkg, String name) {
-    this.pkg = pkg;
-    this.name = name;
-  }
-
-  public String getType() {
-    if (type == null) {
-      // Using StringBuilder like this is about 40% faster than using the +
-      // operator.
-      StringBuilder stringBuilder = new StringBuilder(pkg.length() + name.length() + 1);
-      stringBuilder.append(pkg);
-      stringBuilder.append("/");
-      stringBuilder.append(name);
-      type = stringBuilder.toString();
-    }
-    return type;
-  }
-
-  private void splitType() {
-    String[] packageAndName = type.split("/", 2);
-    pkg = packageAndName[0];
-    name = packageAndName[1];
-  }
-
-  public String getPackage() {
-    if (pkg == null) {
-      splitType();
-    }
-    return pkg;
-  }
-
-  public String getName() {
-    if (name == null) {
-      splitType();
-    }
-    return name;
-  }
-
-  @Override
-  public String toString() {
-    return String.format("MessageIdentifier<%s>", type);
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + ((type == null) ? 0 : type.hashCode());
-    return result;
-  }
-
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj)
-      return true;
-    if (obj == null)
-      return false;
-    if (getClass() != obj.getClass())
-      return false;
-    MessageIdentifier other = (MessageIdentifier) obj;
-    if (type == null) {
-      if (other.type != null)
-        return false;
-    } else if (!type.equals(other.type))
-      return false;
-    return true;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageListener.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageListener.java
deleted file mode 100644
index 6fa0d1e9e70024411ddf2b85586c3246c018ea73..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageListener.java
+++ /dev/null
@@ -1,36 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- *
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-/**
- * A callback for asynchronous message-related operations.
- * 
- * @author damonkohler@google.com (Damon Kohler)
- * 
- * @param <T>
- *          the type of message expected
- */
-public interface MessageListener<T> {
-
-  /**
-   * Called when a new message arrives.
-   * 
-   * @param message
-   *          the new message
-   */
-  void onNewMessage(T message);
-}
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageSerializationFactory.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageSerializationFactory.java
deleted file mode 100644
index 8971583decc731060415d829e03f849dcdc292ee..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageSerializationFactory.java
+++ /dev/null
@@ -1,75 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- */
-public interface MessageSerializationFactory {
-
-  /**
-   * @param messageType
-   *          the type of message that the new {@link MessageSerializer} should
-   *          serialize
-   * @return a new {@link MessageSerializer} for the provided message type
-   */
-  <T> MessageSerializer<T> newMessageSerializer(String messageType);
-
-  /**
-   * @param messageType
-   *          the type of message that the new {@link MessageDeserializer}
-   *          should deserialize
-   * @return a new {@link MessageDeserializer} for the provided message type
-   */
-  <T> MessageDeserializer<T> newMessageDeserializer(String messageType);
-
-  /**
-   * @param serviceType
-   *          the type of service that the new {@link MessageSerializer} should
-   *          serialize requests for
-   * @return a new {@link MessageSerializer} for requests to the provided
-   *         service type
-   */
-  <T> MessageSerializer<T> newServiceRequestSerializer(String serviceType);
-
-  /**
-   * @param serviceType
-   *          the type of service that the new {@link MessageDeserializer}
-   *          should deserialize requests for
-   * @return a new {@link MessageDeserializer} for requests to the provided
-   *         service type
-   */
-  <T> MessageDeserializer<T> newServiceRequestDeserializer(String serviceType);
-
-  /**
-   * @param serviceType
-   *          the type of service that the new {@link MessageSerializer} should
-   *          serialize responses for
-   * @return a new {@link MessageSerializer} for responses from the provided
-   *         service type
-   */
-  <T> MessageSerializer<T> newServiceResponseSerializer(String serviceType);
-
-  /**
-   * @param serviceType
-   *          the type of service that the new {@link MessageDeserializer}
-   *          should deserialize responses for
-   * @return a new {@link MessageDeserializer} for responses from the provided
-   *         service type
-   */
-  <T> MessageDeserializer<T> newServiceResponseDeserializer(String serviceType);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/MessageSerializer.java b/rosjava_bootstrap/src/main/java/org/ros/message/MessageSerializer.java
deleted file mode 100644
index ffeb21804f2bff8b305b40b03e4c5e66f00678e4..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/MessageSerializer.java
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-package org.ros.message;
-
-import org.jboss.netty.buffer.ChannelBuffer;
-
-/**
- * @author damonkohler@google.com (Damon Kohler)
- * 
- * @param <T>
- *          the type of message that the {@link MessageSerializer} can serialize
- */
-public interface MessageSerializer<T> {
-
-  void serialize(T message, ChannelBuffer buffer);
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/Time.java b/rosjava_bootstrap/src/main/java/org/ros/message/Time.java
deleted file mode 100644
index 7805610ced848ddd9de460be257984cfd5aa219d..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/Time.java
+++ /dev/null
@@ -1,156 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- * 
- * Copyright (c) 2008, Willow Garage, Inc. All rights reserved.
- * 
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * 
- * * Redistributions of source code must retain the above copyright notice, this
- * list of conditions and the following disclaimer. * Redistributions in binary
- * form must reproduce the above copyright notice, this list of conditions and
- * the following disclaimer in the documentation and/or other materials provided
- * with the distribution. * Neither the name of Willow Garage, Inc. nor the
- * names of its contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- * 
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-package org.ros.message;
-
-/**
- * ROS Time representation. Time and Time are primitive types in ROS. ROS
- * represents each as two 32-bit integers: seconds and nanoseconds since epoch.
- * 
- * @see "http://www.ros.org/wiki/msg"
- * 
- * @author Jason Wolfe
- * @author kwc@willowgarage.com (Ken Conley)
- */
-public class Time implements Comparable<Time> {
-
-  public int secs;
-  public int nsecs;
-
-  public Time() {
-    secs = 0;
-    nsecs = 0;
-  }
-
-  public Time(int secs, int nsecs) {
-    this.secs = secs;
-    this.nsecs = nsecs;
-    normalize();
-  }
-
-  public Time(double secs) {
-    this.secs = (int) secs;
-    this.nsecs = (int) ((secs - this.secs) * 1000000000);
-    normalize();
-  }
-
-  public Time(Time t) {
-    this.secs = t.secs;
-    this.nsecs = t.nsecs;
-  }
-
-  public Time add(Duration d) {
-    return new Time(secs + d.secs, nsecs + d.nsecs);
-  }
-
-  public Time subtract(Duration d) {
-    return new Time(secs - d.secs, nsecs - d.nsecs);
-  }
-
-  public Duration subtract(Time t) {
-    return new Duration(secs - t.secs, nsecs - t.nsecs);
-  }
-
-  public static Time fromMillis(long timeInMillis) {
-    int secs = (int) (timeInMillis / 1000);
-    int nsecs = (int) (timeInMillis % 1000) * 1000000;
-    return new Time(secs, nsecs);
-  }
-
-  public static Time fromNano(long timeInNs) {
-    int secs = (int) (timeInNs / 1000000000);
-    int nsecs = (int) (timeInNs % 1000000000);
-    return new Time(secs, nsecs);
-  }
-
-  @Override
-  public String toString() {
-    return secs + ":" + nsecs;
-  }
-
-  public double toSeconds() {
-    return totalNsecs() / 1e9;
-  }
-
-  public long totalNsecs() {
-    return ((long) secs) * 1000000000 + nsecs;
-  }
-
-  public boolean isZero() {
-    return totalNsecs() == 0;
-  }
-
-  public void normalize() {
-    while (nsecs < 0) {
-      nsecs += 1000000000;
-      secs -= 1;
-    }
-    while (nsecs >= 1000000000) {
-      nsecs -= 1000000000;
-      secs += 1;
-    }
-  }
-
-  @Override
-  public int hashCode() {
-    final int prime = 31;
-    int result = 1;
-    result = prime * result + nsecs;
-    result = prime * result + secs;
-    return result;
-  }
-
-  /**
-   * Check for equality between {@link Time} objects.
-   * <p>
-   * This method does not normalize {@link Time} representations, so fields must match
-   * exactly.
-   */
-  @Override
-  public boolean equals(Object obj) {
-    if (this == obj) return true;
-    if (obj == null) return false;
-    if (getClass() != obj.getClass()) return false;
-    Time other = (Time) obj;
-    if (nsecs != other.nsecs) return false;
-    if (secs != other.secs) return false;
-    return true;
-  }
-
-  @Override
-  public int compareTo(Time t) {
-    if ((secs > t.secs) || ((secs == t.secs) && nsecs > t.nsecs)) {
-      return 1;
-    }
-    if ((secs == t.secs) && (nsecs == t.nsecs)) {
-      return 0;
-    }
-    return -1;
-  }
-}
diff --git a/rosjava_bootstrap/src/main/java/org/ros/message/package-info.java b/rosjava_bootstrap/src/main/java/org/ros/message/package-info.java
deleted file mode 100644
index 2f5756111a5418b869da16b11cea2a6f3e9aec71..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/message/package-info.java
+++ /dev/null
@@ -1,22 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-/**
- * Provides the classes for representing messages.
- * 
- * @see <a href="http://ros.org/wiki/Messages">messages documentation</a>
- */
-package org.ros.message;
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/main/java/org/ros/package-info.java b/rosjava_bootstrap/src/main/java/org/ros/package-info.java
deleted file mode 100644
index 14a719a824b531976ce64a91e1cb87ec3e5196b0..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/main/java/org/ros/package-info.java
+++ /dev/null
@@ -1,22 +0,0 @@
-/*
- * Copyright (C) 2012 Google Inc.
- * 
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- * 
- * http://www.apache.org/licenses/LICENSE-2.0
- * 
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-/**
- * Provides the classes that are core to ROS development in Java.
- * 
- *  @see <a href="http://docs.rosjava.googlecode.com/hg/rosjava_core/html/index.html">rosjava_core documentation</a>
- */
-package org.ros;
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Point.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Point.msg
deleted file mode 100644
index f1d3a71a853c668f066de795ba5e0f4458f3f1c0..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Point.msg
+++ /dev/null
@@ -1,4 +0,0 @@
-# This contains the position of a point in free space
-float64 x
-float64 y
-float64 z
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Pose.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Pose.msg
deleted file mode 100644
index b81919c7b256667be00908b866f8bf63404256c6..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Pose.msg
+++ /dev/null
@@ -1,3 +0,0 @@
-# A representation of pose in free space, composed of postion and orientation. 
-Point position
-Quaternion orientation
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/PoseWithCovariance.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/PoseWithCovariance.msg
deleted file mode 100644
index 86bc45adbb5d7d64e90556ac1f24ca8f725313cd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/PoseWithCovariance.msg
+++ /dev/null
@@ -1,9 +0,0 @@
-# This represents a pose in free space with uncertainty.
-
-Pose pose
-
-# Row-major representation of the 6x6 covariance matrix
-# The orientation parameters use a fixed-axis representation.
-# In order, the parameters are:
-# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
-float64[36] covariance
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Quaternion.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Quaternion.msg
deleted file mode 100644
index 9f4fde2bf4c13dc86a95688e4b5254aaec186e2a..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Quaternion.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# This represents an orientation in free space in quaternion form.
-
-float64 x
-float64 y
-float64 z
-float64 w
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Twist.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Twist.msg
deleted file mode 100644
index dc27ca14a7d69f720faff92171456cc71d4fc967..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Twist.msg
+++ /dev/null
@@ -1,3 +0,0 @@
-# This expresses velocity in free space broken into it's linear and angular parts. 
-Vector3  linear
-Vector3  angular
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/TwistWithCovariance.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/TwistWithCovariance.msg
deleted file mode 100644
index 6d89780154c01faf43175b19363047dcaa9cb73b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/TwistWithCovariance.msg
+++ /dev/null
@@ -1,9 +0,0 @@
-# This expresses velocity in free space with uncertianty.
-
-Twist twist
-
-# Row-major representation of the 6x6 covariance matrix
-# The orientation parameters use a fixed-axis representation.
-# In order, the parameters are:
-# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
-float64[36] covariance
diff --git a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Vector3.msg b/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Vector3.msg
deleted file mode 100644
index 00dd4cbac99e2729865cd00faff2ac482c0794cd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/geometry_msgs/msg/Vector3.msg
+++ /dev/null
@@ -1,5 +0,0 @@
-# This represents a vector in free space. 
-
-float64 x
-float64 y
-float64 z
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/nav_msgs/msg/Odometry.msg b/rosjava_bootstrap/src/test/resources/nav_msgs/msg/Odometry.msg
deleted file mode 100644
index 73578ed85765ca14b040dc888d9cb148530a95d3..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/nav_msgs/msg/Odometry.msg
+++ /dev/null
@@ -1,7 +0,0 @@
-# This represents an estimate of a position and velocity in free space.  
-# The pose in this message should be specified in the coordinate frame given by header.frame_id.
-# The twist in this message should be specified in the coordinate frame given by the child_frame_id
-Header header
-string child_frame_id
-geometry_msgs/PoseWithCovariance pose
-geometry_msgs/TwistWithCovariance twist
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Bool.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Bool.msg
deleted file mode 100644
index f7cabb94fc04ac5f83ca8f219357b439f29d002f..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Bool.msg
+++ /dev/null
@@ -1 +0,0 @@
-bool data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Byte.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Byte.msg
deleted file mode 100644
index d993b3455539598fdc5db3365a4534ed9f125b5d..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Byte.msg
+++ /dev/null
@@ -1 +0,0 @@
-byte data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/ByteMultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/ByteMultiArray.msg
deleted file mode 100644
index bb00bd348bc726b4bf52ae12c1fe740855447b95..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/ByteMultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-byte[]            data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Char.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Char.msg
deleted file mode 100644
index 39a1d46a97c419a2b8ab45b30c68758ed03b905b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Char.msg
+++ /dev/null
@@ -1 +0,0 @@
-char data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/ColorRGBA.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/ColorRGBA.msg
deleted file mode 100644
index 182dbc8349abec122d95436cb840906503f569f2..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/ColorRGBA.msg
+++ /dev/null
@@ -1,4 +0,0 @@
-float32 r
-float32 g
-float32 b
-float32 a
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Duration.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Duration.msg
deleted file mode 100644
index f13931ec8a7937ca624ff91af7f861559b5fc3fe..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Duration.msg
+++ /dev/null
@@ -1 +0,0 @@
-duration data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Empty.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Empty.msg
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float32.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float32.msg
deleted file mode 100644
index e89740534bd9c0344c18709de0c29667620295bd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float32.msg
+++ /dev/null
@@ -1 +0,0 @@
-float32 data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float32MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float32MultiArray.msg
deleted file mode 100644
index 915830846dd023a111abd8ad2831d982b9c85a82..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float32MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-float32[]         data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float64.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float64.msg
deleted file mode 100644
index cd09d39b8caedf067b9548d62ecab3c73b6ecace..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float64.msg
+++ /dev/null
@@ -1 +0,0 @@
-float64 data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float64MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float64MultiArray.msg
deleted file mode 100644
index 0a13b928fd70d116defc17ec0acc09a6296b57ff..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Float64MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-float64[]         data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Header.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Header.msg
deleted file mode 100644
index b2f34f6f1d15f22149dae16e5e6bbf190a89a0d8..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Header.msg
+++ /dev/null
@@ -1,15 +0,0 @@
-# Standard metadata for higher-level stamped data types.
-# This is generally used to communicate timestamped data 
-# in a particular coordinate frame.
-# 
-# sequence ID: consecutively increasing ID 
-uint32 seq
-#Two-integer timestamp that is expressed as:
-# * stamp.secs: seconds (stamp_secs) since epoch
-# * stamp.nsecs: nanoseconds since stamp_secs
-# time-handling sugar is provided by the client library
-time stamp
-#Frame this data is associated with
-# 0: no frame
-# 1: global frame
-string frame_id
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int16.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int16.msg
deleted file mode 100644
index c4389faf706f189e64bc576af0f7788f06d16c86..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int16.msg
+++ /dev/null
@@ -1 +0,0 @@
-int16 data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int16MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int16MultiArray.msg
deleted file mode 100644
index d2ddea1d1d6a69a15cb17e434900a1afbadaac89..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int16MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-int16[]           data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int32.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int32.msg
deleted file mode 100644
index 0ecfe35f5f480f463e0b26e696c4f0e858aba06c..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int32.msg
+++ /dev/null
@@ -1 +0,0 @@
-int32 data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int32MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int32MultiArray.msg
deleted file mode 100644
index af60abda3a697bac5e596b23b04038414258188a..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int32MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-int32[]           data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int64.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int64.msg
deleted file mode 100644
index 6961e00f52989d8e03f54e0a0e0333ae470e6508..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int64.msg
+++ /dev/null
@@ -1 +0,0 @@
-int64 data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int64MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int64MultiArray.msg
deleted file mode 100644
index f4f35e171b316dacbb0eb3a80e20885977171ebd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int64MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-int64[]           data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int8.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int8.msg
deleted file mode 100644
index 1e42e554feea25175f15af74433d802e86ed0180..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int8.msg
+++ /dev/null
@@ -1 +0,0 @@
-int8 data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int8MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int8MultiArray.msg
deleted file mode 100644
index a59a37259e5e97c8dbee0072f4e6c282d7fc8fd3..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Int8MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-int8[]            data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/MultiArrayDimension.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/MultiArrayDimension.msg
deleted file mode 100644
index 08240462c4315969a5a8cde9292683c51865a5d3..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/MultiArrayDimension.msg
+++ /dev/null
@@ -1,3 +0,0 @@
-string label   # label of given dimension
-uint32 size    # size of given dimension (in type units)
-uint32 stride  # stride of given dimension
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/MultiArrayLayout.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/MultiArrayLayout.msg
deleted file mode 100644
index 5437f8542af613c0058e380c27ab59cb5ebb7df0..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/MultiArrayLayout.msg
+++ /dev/null
@@ -1,26 +0,0 @@
-# The multiarray declares a generic multi-dimensional array of a
-# particular data type.  Dimensions are ordered from outer most
-# to inner most.
-
-MultiArrayDimension[] dim # Array of dimension properties
-uint32 data_offset        # padding bytes at front of data
-
-# Accessors should ALWAYS be written in terms of dimension stride
-# and specified outer-most dimension first.
-# 
-# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
-#
-# A standard, 3-channel 640x480 image with interleaved color channels
-# would be specified as:
-#
-# dim[0].label  = "height"
-# dim[0].size   = 480
-# dim[0].stride = 3*640*480 = 921600  (note dim[0] stride is just size of image)
-# dim[1].label  = "width"
-# dim[1].size   = 640
-# dim[1].stride = 3*640 = 1920
-# dim[2].label  = "channel"
-# dim[2].size   = 3
-# dim[2].stride = 3
-#
-# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/String.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/String.msg
deleted file mode 100644
index ae721739e8fa7035347d3fed3cca1b137e670c97..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/String.msg
+++ /dev/null
@@ -1 +0,0 @@
-string data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Time.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/Time.msg
deleted file mode 100644
index 7f8f721711fbbc620fa7f6b58a9f89d5667281be..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/Time.msg
+++ /dev/null
@@ -1 +0,0 @@
-time data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt16.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt16.msg
deleted file mode 100644
index 87d0c44eb59dca29f419aaa77801b4fbc278f9f6..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt16.msg
+++ /dev/null
@@ -1 +0,0 @@
-uint16 data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt16MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt16MultiArray.msg
deleted file mode 100644
index f38970b656cf1160e292f9effc8f5d8c3281a12b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt16MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-uint16[]            data        # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt32.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt32.msg
deleted file mode 100644
index b6c696b421e4a4c89c7f1420fbaa15af83913093..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt32.msg
+++ /dev/null
@@ -1 +0,0 @@
-uint32 data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt32MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt32MultiArray.msg
deleted file mode 100644
index b2bb0771f0208bc3c45210a918d689d5a24b53a7..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt32MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-uint32[]          data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt64.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt64.msg
deleted file mode 100644
index 2eb1afad37e320a366f7b0296fb207569a30db47..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt64.msg
+++ /dev/null
@@ -1 +0,0 @@
-uint64 data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt64MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt64MultiArray.msg
deleted file mode 100644
index 30d0cd92854159d4cc3fa5e996763cc08e9dcdf9..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt64MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-uint64[]          data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt8.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt8.msg
deleted file mode 100644
index 5eefd870db82c99cf7d62e7ccff1824c114bd462..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt8.msg
+++ /dev/null
@@ -1 +0,0 @@
-uint8 data
diff --git a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt8MultiArray.msg b/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt8MultiArray.msg
deleted file mode 100644
index 31f7d6a213995f216f4d124f1d6402852d1572b2..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_msgs/msg/UInt8MultiArray.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Please look at the MultiArrayLayout message definition for
-# documentation on all multiarrays.
-
-MultiArrayLayout  layout        # specification of data layout
-uint8[]           data          # array of data
-
diff --git a/rosjava_bootstrap/src/test/resources/std_srvs/srv/Empty.srv b/rosjava_bootstrap/src/test/resources/std_srvs/srv/Empty.srv
deleted file mode 100644
index 73b314ff7c704c18889cf90fdc024716c634adb6..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/std_srvs/srv/Empty.srv
+++ /dev/null
@@ -1 +0,0 @@
----
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/Composite.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/Composite.msg
deleted file mode 100644
index 4629d3e56c7c03e55052196f34f3a5976024f524..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/Composite.msg
+++ /dev/null
@@ -1,3 +0,0 @@
-# composite message. required for testing import calculation in generators
-CompositeA a
-CompositeB b
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/CompositeA.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/CompositeA.msg
deleted file mode 100644
index 9f4fde2bf4c13dc86a95688e4b5254aaec186e2a..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/CompositeA.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# This represents an orientation in free space in quaternion form.
-
-float64 x
-float64 y
-float64 z
-float64 w
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/CompositeB.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/CompositeB.msg
deleted file mode 100644
index fb689bc8225e2c6f60b45c852c7f19da3dcd00cb..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/CompositeB.msg
+++ /dev/null
@@ -1,4 +0,0 @@
-# copy of geometry_msgs/Point for testing
-float64 x
-float64 y
-float64 z
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestArrays.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/TestArrays.msg
deleted file mode 100644
index 2d7493fe41614d7fed5ba02067c030377780d85d..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestArrays.msg
+++ /dev/null
@@ -1,10 +0,0 @@
-# caller_id of most recent node to send this message
-string caller_id
-# caller_id of the original node to send this message
-string orig_caller_id
-
-int32[] int32_array
-float32[] float32_array
-time[] time_array
-TestString[] test_string_array
-# TODO: array of arrays
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestHeader.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/TestHeader.msg
deleted file mode 100644
index 22897c3b85330325819e6e8fee8ab8198ba6fe00..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestHeader.msg
+++ /dev/null
@@ -1,8 +0,0 @@
-Header header
-
-# caller_id of most recent node to send this message
-string caller_id
-# caller_id of the original node to send this message
-string orig_caller_id
-
-byte auto_header # autoset header on response
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestPrimitives.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/TestPrimitives.msg
deleted file mode 100644
index 815dd5b0d18f9b94da8c8952c36cb0738d5d6438..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestPrimitives.msg
+++ /dev/null
@@ -1,21 +0,0 @@
-# Integration test message of all primitive types
-
-# caller_id of most recent node to send this message
-string caller_id
-# caller_id of the original node to send this message
-string orig_caller_id
-
-string str
-byte b
-int16 int16
-int32 int32
-int64 int64
-char c
-uint16 uint16
-uint32 uint32
-uint64 uint64
-float32 float32
-float64 float64
-time t
-duration d
-
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestString.msg b/rosjava_bootstrap/src/test/resources/test_ros/msg/TestString.msg
deleted file mode 100644
index 4ab04385050da20743d887191f80a17361d0f4c3..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/msg/TestString.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-# Integration test message
-# caller_id of most recent node to send this message
-string caller_id
-# caller_id of the original node to send this message
-string orig_caller_id
-string data
diff --git a/rosjava_bootstrap/src/test/resources/test_ros/srv/AddTwoInts.srv b/rosjava_bootstrap/src/test/resources/test_ros/srv/AddTwoInts.srv
deleted file mode 100644
index 3a68808ee591a3623cbf5e553eed28bac5233be8..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_ros/srv/AddTwoInts.srv
+++ /dev/null
@@ -1,4 +0,0 @@
-int64 a
-int64 b
----
-int64 sum
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/ArrayVal.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/ArrayVal.msg
deleted file mode 100644
index 4a34dd1bb8c84ef12a33f1782a27acaaa8dc8812..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/ArrayVal.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-Val[] vals
-#Val[10] vals_fixed
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/EmbedTest.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/EmbedTest.msg
deleted file mode 100644
index e1962cd4e10b88807c085907284686a85e1b9026..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/EmbedTest.msg
+++ /dev/null
@@ -1,6 +0,0 @@
-std_msgs/String str1
-std_msgs/Int32 int1
-std_msgs/Int32[] ints
-Val val
-Val[] vals
-ArrayVal[] arrayval
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/Floats.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/Floats.msg
deleted file mode 100644
index 6bd8052d3121617bd05bb32247181ab8819791a1..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/Floats.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-# exact copy of rospy_tutorials/Floats, used for testing
-float32[] data
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/HeaderHeaderVal.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/HeaderHeaderVal.msg
deleted file mode 100644
index 6882d7ac4ae5e42bab89bdb212d21aba8dedf918..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/HeaderHeaderVal.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-Header header
-HeaderVal val
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/HeaderVal.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/HeaderVal.msg
deleted file mode 100644
index 91f99b2545dbf8b10e20be09e7cbbd0478531d12..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/HeaderVal.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-Header header
-string val
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/PythonKeyword.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/PythonKeyword.msg
deleted file mode 100644
index 0949ea888777ebf179376c7c044c8886c9eac1bd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/PythonKeyword.msg
+++ /dev/null
@@ -1 +0,0 @@
-int32 yield
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TestConstants.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/TestConstants.msg
deleted file mode 100644
index 344afc3840a05ca3247d780a54893fe263e73939..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TestConstants.msg
+++ /dev/null
@@ -1,15 +0,0 @@
-float32 A=-123.0
-float32 B=124.0
-float64 C=125.0
-int32 X=123
-int32 Y=-123
-uint32 Z=124
-string FOO=foo
-string SINGLEQUOTE='hi
-string DOUBLEQUOTE="hello" there
-string MULTIQUOTE="hello" 'goodbye'
-string EXAMPLE="#comments" are ignored, and leading and trailing whitespace removed
-string WHITESPACE= strip  
-string EMPTY= 
-bool TRUE=1
-bool FALSE=0
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TestFixedArray.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/TestFixedArray.msg
deleted file mode 100644
index 005aa94af24fd1e3cfac5215cf76a6a6b9523999..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TestFixedArray.msg
+++ /dev/null
@@ -1,16 +0,0 @@
-float32[1] f32_1
-float32[3] f32_3
-float64[1] f64_1
-float64[3] f64_3
-int8[1] i8_1
-int8[3] i8_3
-uint8[1] u8_1
-uint8[3] u8_3
-int32[1] i32_1
-int32[3] i32_3
-uint32[1] u32_1
-uint32[3] u32_3
-string[1] s_1
-string[3] s_3
-bool[1] b_1
-bool[3] b_3
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveImport.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveImport.msg
deleted file mode 100644
index bf33d172859640df342b6ea66d89d5cfed850537..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveImport.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-# Bug #2133/2139: EmbedTest uses std_msgs, so TransitiveImport needs it as well
-EmbedTest data
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveMsg1.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveMsg1.msg
deleted file mode 100644
index f41ed0cf3ce5662220a8a4ce94d31e9edb521320..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveMsg1.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-TransitiveMsg2 msg2
-
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveMsg2.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveMsg2.msg
deleted file mode 100644
index 378a1c582851bfb70ebde18285b4b527599f33cb..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/TransitiveMsg2.msg
+++ /dev/null
@@ -1 +0,0 @@
-test_ros/Composite data
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/msg/Val.msg b/rosjava_bootstrap/src/test/resources/test_rospy/msg/Val.msg
deleted file mode 100644
index c11841ad234e1b31fc7dde9c26a5249b7181c02a..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/msg/Val.msg
+++ /dev/null
@@ -1 +0,0 @@
-string val
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/ConstantsMultiplex.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/ConstantsMultiplex.srv
deleted file mode 100644
index b955445414b95f3c56ac4e676e2d20e350b6acb4..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/ConstantsMultiplex.srv
+++ /dev/null
@@ -1,26 +0,0 @@
-byte BYTE_X=0
-byte BYTE_Y=15
-byte BYTE_Z=5
-int32 INT32_X=0
-int32 INT32_Y=-12345678
-int32 INT32_Z=12345678
-uint32 UINT32_X=0
-uint32 UINT32_Y=12345678
-uint32 UINT32_Z=1
-float32 FLOAT32_X=0.0
-float32 FLOAT32_Y=-3.14159
-float32 FLOAT32_Z=12345.78
-byte SELECT_X=1
-byte SELECT_Y=2
-byte SELECT_Z=3
-byte selection
----
-# test response constants as well
-byte CONFIRM_X=1
-byte CONFIRM_Y=2
-byte CONFIRM_Z=3
-byte select_confirm
-byte ret_byte
-int32 ret_int32
-uint32 ret_uint32
-float32 ret_float32
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptyReqSrv.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptyReqSrv.srv
deleted file mode 100644
index 1f2c1eb6ac0db364f9ad16172625c6002c52d06e..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptyReqSrv.srv
+++ /dev/null
@@ -1,2 +0,0 @@
----
-int32 fake_secret
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptyRespSrv.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptyRespSrv.srv
deleted file mode 100644
index 6ef29bc8d831056d98c78522e1393160490ff326..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptyRespSrv.srv
+++ /dev/null
@@ -1,2 +0,0 @@
-int32 fake_secret
----
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptySrv.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptySrv.srv
deleted file mode 100644
index ed97d539c095cf1413af30cc23dea272095b97dd..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/EmptySrv.srv
+++ /dev/null
@@ -1 +0,0 @@
----
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/ListReturn.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/ListReturn.srv
deleted file mode 100644
index 311e806433675ad02b272023067b9e9444dc7349..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/ListReturn.srv
+++ /dev/null
@@ -1,7 +0,0 @@
-# test case for having single list return value
-int32 a
-int32 b
-int32 c
-int32 d
----
-int32[] abcd
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/MultipleAddTwoInts.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/MultipleAddTwoInts.srv
deleted file mode 100644
index 522a482621cf430cf3ed8318667ab6896ffee9ef..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/MultipleAddTwoInts.srv
+++ /dev/null
@@ -1,8 +0,0 @@
-# test case for having multiple return values
-int32 a
-int32 b
-int32 c
-int32 d
----
-int32 ab
-int32 cd
\ No newline at end of file
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/StringString.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/StringString.srv
deleted file mode 100644
index a9242d416e849ba58184d8f030fef12fd5cc7a0b..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/StringString.srv
+++ /dev/null
@@ -1,4 +0,0 @@
-std_msgs/String str
-Val str2
----
-std_msgs/String str
diff --git a/rosjava_bootstrap/src/test/resources/test_rospy/srv/TransitiveSrv.srv b/rosjava_bootstrap/src/test/resources/test_rospy/srv/TransitiveSrv.srv
deleted file mode 100644
index 7c62a01e55ac608226fef8f4c3fd69fa13e2390f..0000000000000000000000000000000000000000
--- a/rosjava_bootstrap/src/test/resources/test_rospy/srv/TransitiveSrv.srv
+++ /dev/null
@@ -1,4 +0,0 @@
-test_rospy/TransitiveMsg1 msg
----
-int32 a
-
diff --git a/rosjava_messages/build.gradle b/rosjava_messages/build.gradle
deleted file mode 100644
index 5f8c702b1d1b9e0aba0d8403d39449a5f2fcc8d2..0000000000000000000000000000000000000000
--- a/rosjava_messages/build.gradle
+++ /dev/null
@@ -1,38 +0,0 @@
-/*
- * Copyright (C) 2011 Google Inc.
- *
- * Licensed under the Apache License, Version 2.0 (the "License"); you may not
- * use this file except in compliance with the License. You may obtain a copy of
- * the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations under
- * the License.
- */
-
-dependencies {
-  compile project(':rosjava_bootstrap')
-}
-
-
-task generateSources(type: JavaExec) {
-  def outputDir = "${buildDir}/generated-src"
-  outputs.dir file(outputDir)
-  args outputDir
-  classpath = configurations.runtime
-  main = 'org.ros.internal.message.GenerateInterfaces'
-}
-
-compileJava.source generateSources.outputs.files
-
-eclipse.classpath.file {
-  withXml {
-    // TODO(damonkohler): Avoid repetition of build directory. This is
-    // necessary because Eclipse wants a project relative path.
-    it.asNode().appendNode('classpathentry', [kind: 'src', path: 'build/generated-src'])
-  }
-}
diff --git a/rosjava_test/src/main/java/org/ros/ParameterServerTestNode.java b/rosjava_test/src/main/java/org/ros/ParameterServerTestNode.java
index 6c139d07a62d4cf9247b34bf2c8ae1c0ec11a015..523f0b08fd59204fb879826f2ca00f2943181b62 100644
--- a/rosjava_test/src/main/java/org/ros/ParameterServerTestNode.java
+++ b/rosjava_test/src/main/java/org/ros/ParameterServerTestNode.java
@@ -55,10 +55,10 @@ public class ParameterServerTestNode extends AbstractNodeMain {
         connectedNode.newPublisher("bool", std_msgs.Bool._TYPE);
     final Publisher<std_msgs.Float64> pub_float =
         connectedNode.newPublisher("float", std_msgs.Float64._TYPE);
-    final Publisher<test_ros.Composite> pub_composite =
-        connectedNode.newPublisher("composite", test_ros.Composite._TYPE);
-    final Publisher<test_ros.TestArrays> pub_list =
-        connectedNode.newPublisher("list", test_ros.TestArrays._TYPE);
+    final Publisher<rosjava_test_msgs.Composite> pub_composite =
+        connectedNode.newPublisher("composite", rosjava_test_msgs.Composite._TYPE);
+    final Publisher<rosjava_test_msgs.TestArrays> pub_list =
+        connectedNode.newPublisher("list", rosjava_test_msgs.TestArrays._TYPE);
 
     ParameterTree param = connectedNode.getParameterTree();
 
@@ -90,8 +90,8 @@ public class ParameterServerTestNode extends AbstractNodeMain {
     float_m.setData(param.getDouble(resolver.resolve("float")));
     log.info("float: " + float_m.getData());
 
-    final test_ros.Composite composite_m =
-        topicMessageFactory.newFromType(test_ros.Composite._TYPE);
+    final rosjava_test_msgs.Composite composite_m =
+        topicMessageFactory.newFromType(rosjava_test_msgs.Composite._TYPE);
     Map composite_map = param.getMap(resolver.resolve("composite"));
     composite_m.getA().setW((Double) ((Map) composite_map.get("a")).get("w"));
     composite_m.getA().setX((Double) ((Map) composite_map.get("a")).get("x"));
@@ -101,7 +101,7 @@ public class ParameterServerTestNode extends AbstractNodeMain {
     composite_m.getB().setY((Double) ((Map) composite_map.get("b")).get("y"));
     composite_m.getB().setZ((Double) ((Map) composite_map.get("b")).get("z"));
 
-    final test_ros.TestArrays list_m = topicMessageFactory.newFromType(test_ros.TestArrays._TYPE);
+    final rosjava_test_msgs.TestArrays list_m = topicMessageFactory.newFromType(rosjava_test_msgs.TestArrays._TYPE);
     // only using the integer part for easier (non-float) comparison
     @SuppressWarnings("unchecked")
     List<Integer> list = (List<Integer>) param.getList(resolver.resolve("list"));
diff --git a/rosjava_test/src/main/java/org/ros/PassthroughTestNode.java b/rosjava_test/src/main/java/org/ros/PassthroughTestNode.java
index 9ad051835d5154adc456aeaa96e82516f048b532..2d251bdd11d230f1000224e4a6132ba49bb91ac5 100644
--- a/rosjava_test/src/main/java/org/ros/PassthroughTestNode.java
+++ b/rosjava_test/src/main/java/org/ros/PassthroughTestNode.java
@@ -67,31 +67,31 @@ public class PassthroughTestNode extends AbstractNodeMain {
     int64Subscriber.addMessageListener(int64_cb);
 
     // TestHeader pass through
-    final Publisher<test_ros.TestHeader> pub_header =
-        connectedNode.newPublisher("test_header_out", test_ros.TestHeader._TYPE);
-    MessageListener<test_ros.TestHeader> header_cb = new MessageListener<test_ros.TestHeader>() {
+    final Publisher<rosjava_test_msgs.TestHeader> pub_header =
+        connectedNode.newPublisher("test_header_out", rosjava_test_msgs.TestHeader._TYPE);
+    MessageListener<rosjava_test_msgs.TestHeader> header_cb = new MessageListener<rosjava_test_msgs.TestHeader>() {
       @Override
-      public void onNewMessage(test_ros.TestHeader m) {
+      public void onNewMessage(rosjava_test_msgs.TestHeader m) {
         m.setOrigCallerId(m.getCallerId());
         m.setCallerId(connectedNode.getName().toString());
         pub_header.publish(m);
       }
     };
-    Subscriber<test_ros.TestHeader> testHeaderSubscriber =
-        connectedNode.newSubscriber("test_header_in", "test_ros/TestHeader");
+    Subscriber<rosjava_test_msgs.TestHeader> testHeaderSubscriber =
+        connectedNode.newSubscriber("test_header_in", "rosjava_test_msgs/TestHeader");
     testHeaderSubscriber.addMessageListener(header_cb);
 
     // TestComposite pass through
-    final Publisher<test_ros.Composite> pub_composite =
-        connectedNode.newPublisher("composite_out", "test_ros/Composite");
-    MessageListener<test_ros.Composite> composite_cb = new MessageListener<test_ros.Composite>() {
+    final Publisher<rosjava_test_msgs.Composite> pub_composite =
+        connectedNode.newPublisher("composite_out", "rosjava_test_msgs/Composite");
+    MessageListener<rosjava_test_msgs.Composite> composite_cb = new MessageListener<rosjava_test_msgs.Composite>() {
       @Override
-      public void onNewMessage(test_ros.Composite m) {
+      public void onNewMessage(rosjava_test_msgs.Composite m) {
         pub_composite.publish(m);
       }
     };
-    Subscriber<test_ros.Composite> compositeSubscriber =
-        connectedNode.newSubscriber("composite_in", "test_ros/Composite");
+    Subscriber<rosjava_test_msgs.Composite> compositeSubscriber =
+        connectedNode.newSubscriber("composite_in", "rosjava_test_msgs/Composite");
     compositeSubscriber.addMessageListener(composite_cb);
   }
 }
diff --git a/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Client.java b/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Client.java
index 0c3d5fc9d5ce4a6395bde7453280c8d4e17c30a7..1f1e69a6deee2ce9828635e573e61229ab9bbf77 100644
--- a/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Client.java
+++ b/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Client.java
@@ -40,18 +40,18 @@ public class Client extends AbstractNodeMain {
 
   @Override
   public void onStart(final ConnectedNode connectedNode) {
-    ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
+    ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
     try {
-      serviceClient = connectedNode.newServiceClient("add_two_ints", test_ros.AddTwoInts._TYPE);
+      serviceClient = connectedNode.newServiceClient("add_two_ints", rosjava_test_msgs.AddTwoInts._TYPE);
     } catch (ServiceNotFoundException e) {
       throw new RosRuntimeException(e);
     }
-    final test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
+    final rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
     request.setA(2);
     request.setB(2);
-    serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
+    serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
       @Override
-      public void onSuccess(test_ros.AddTwoIntsResponse response) {
+      public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
         connectedNode.getLog().info(
             String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum()));
       }
diff --git a/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java b/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
index a53109fea08d3f608eae3039cd510fbaa05c2ff5..5a313bfbba92cb3899dfc6ab18fcf42b11018f43 100644
--- a/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
+++ b/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
@@ -37,11 +37,11 @@ public class Server extends AbstractNodeMain {
 
   @Override
   public void onStart(ConnectedNode connectedNode) {
-    connectedNode.newServiceServer("add_two_ints", test_ros.AddTwoInts._TYPE,
-        new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
+    connectedNode.newServiceServer("add_two_ints", rosjava_test_msgs.AddTwoInts._TYPE,
+        new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
           @Override
           public void
-              build(test_ros.AddTwoIntsRequest request, test_ros.AddTwoIntsResponse response) {
+              build(rosjava_test_msgs.AddTwoIntsRequest request, rosjava_test_msgs.AddTwoIntsResponse response) {
             response.setSum(request.getA() + request.getB());
           }
         });
diff --git a/settings.gradle b/settings.gradle
index f6287ece6b180af6944d37b269629279352fca28..9377ec995a4ae57905737d91d3922cc20a28dde0 100644
--- a/settings.gradle
+++ b/settings.gradle
@@ -14,8 +14,10 @@
  * the License.
  */
 
-include 'rosjava_bootstrap', 'rosjava_messages', 'apache_xmlrpc_common',
-        'apache_xmlrpc_client', 'apache_xmlrpc_server', 'rosjava',
-        'rosjava_geometry', 'rosjava_tutorial_pubsub',
+include 'apache_xmlrpc_common', 'apache_xmlrpc_client', 'apache_xmlrpc_server',
+        'rosjava', 'rosjava_geometry', 'rosjava_tutorial_pubsub',
         'rosjava_tutorial_services', 'rosjava_tutorial_right_hand_rule',
         'rosjava_benchmarks', 'rosjava_test', 'docs'
+
+include 'message_generation_tests'
+        
\ No newline at end of file