diff --git a/CMakeLists.txt b/CMakeLists.txt
index c93f34b2345f2559acc408775d6bd047a3b665a9..b4c80f6eedc4446d9ed85aae893379e78d2defea 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,7 +1,7 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(rosjava_core)
 
-find_package(catkin REQUIRED rosjava_tools)
+find_package(catkin REQUIRED rosjava_build_tools)
 
 catkin_rosjava_setup(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/build.gradle b/rosjava/build.gradle
index ba87144cb1761a6fb764580b202bbda16d7d1a8e..b2b44a132b527a5038414812581407f85b42ff66 100644
--- a/rosjava/build.gradle
+++ b/rosjava/build.gradle
@@ -18,7 +18,8 @@ dependencies {
   compile project(':apache_xmlrpc_common')
   compile project(':apache_xmlrpc_server')
   compile project(':apache_xmlrpc_client')
-  compile 'org.ros.rosjava_bootstrap:message_generator:0.1.+'
+  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.+'
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/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_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());
           }
         });