diff --git a/modules/catkin_ws/src/car/CMakeLists.txt b/modules/catkin_ws/src/car/CMakeLists.txt
index 1521b22e02ee5b06e00f9e1e4d9445fb39dbc52d..2a033a1d9443d40d8ef2c601b84c329aaf1c267e 100644
--- a/modules/catkin_ws/src/car/CMakeLists.txt
+++ b/modules/catkin_ws/src/car/CMakeLists.txt
@@ -78,6 +78,8 @@ set(MAIN_NODE_SOURCE_FILES
         src/mainNode/mainNode.cpp
         include/mainNode/mainNode.h include/mainNode/PlatoonController.h src/mainNode/PlatoonController.cpp)
 
+message(MAIN_NODE_SOURCE_FILES)
+
 find_package(catkin REQUIRED COMPONENTS
   roscpp
   rospy
diff --git a/modules/catkin_ws/src/car/include/mainNode/PlatoonController.h b/modules/catkin_ws/src/car/include/mainNode/PlatoonController.h
index 703c9513c38bc4e19fb1d9ed9e34ed20853345f8..09916fe02e61aa5e012f53ed30f446df1129406d 100644
--- a/modules/catkin_ws/src/car/include/mainNode/PlatoonController.h
+++ b/modules/catkin_ws/src/car/include/mainNode/PlatoonController.h
@@ -11,6 +11,7 @@ namespace car
 class PlatoonController
 {
 public:
+    void run();
 
 private:
 };
diff --git a/modules/catkin_ws/src/car/include/mainNode/mainNode.h b/modules/catkin_ws/src/car/include/mainNode/mainNode.h
index bf1157b691ccdcf6c7adc82951eed5ff2fe33fb1..34071ea82b1680beeb564ab26112d0ea973c019d 100644
--- a/modules/catkin_ws/src/car/include/mainNode/mainNode.h
+++ b/modules/catkin_ws/src/car/include/mainNode/mainNode.h
@@ -6,7 +6,8 @@
 #include "boost/thread.hpp"
 #include "car/environmentDataMsg.h"
 #include "NotifiableThread.h"
-#include "../../../../../Communication/NetworkingLib/include/Networking.h"
+//#include "../../../../../Communication/NetworkingLib/include/Networking.h"
+#include "PlatoonController.h"
 
 namespace car
 {
@@ -22,12 +23,25 @@ public:
     ~MainNode();
 
 private:
+    std::function<void()> platoonControllerNotify =
+        [this]
+        { platoonControllerThread.notify(); };
+
+    NotifiableThread::Callback platoonControllerRun =
+        [this]
+        { platoonController.run(); };
+
     ros::NodeHandle nh;
     std::string name;
     boost::thread loggerModule;
     ros::Publisher logEnabled;
     ros::Subscriber environmentData;
 
+    //Networking platoonProtocolThread;
+    NotifiableThread platoonControllerThread;
+
+    PlatoonController platoonController;
+
     void environmentDataCallback(const environmentDataMsg::ConstPtr & inMsg);
 };
 }
diff --git a/modules/catkin_ws/src/car/src/mainNode/PlatoonController.cpp b/modules/catkin_ws/src/car/src/mainNode/PlatoonController.cpp
index 5a3dbccf01c57d786a747749896de73f9096e8b9..fcb44c3c1f21b9fbd465cd09872e4ed9dbe02b5e 100644
--- a/modules/catkin_ws/src/car/src/mainNode/PlatoonController.cpp
+++ b/modules/catkin_ws/src/car/src/mainNode/PlatoonController.cpp
@@ -2,3 +2,14 @@
 // Created by philipp on 12.02.18.
 //
 
+#include "../../include/mainNode/PlatoonController.h"
+
+namespace car
+{
+
+void car::PlatoonController::run()
+{
+    // TODO: implementation
+}
+
+}
diff --git a/modules/catkin_ws/src/car/src/mainNode/mainNode.cpp b/modules/catkin_ws/src/car/src/mainNode/mainNode.cpp
index 3c22e498a91e91038f533fca9a059b0eaafde90a..8bef4824b600daf1b26c7c1f8674147a93591b83 100644
--- a/modules/catkin_ws/src/car/src/mainNode/mainNode.cpp
+++ b/modules/catkin_ws/src/car/src/mainNode/mainNode.cpp
@@ -16,23 +16,33 @@ PLUGINLIB_EXPORT_CLASS(car::MainNode, nodelet::Nodelet);
 
 namespace car
 {
-	MainNode::MainNode(ros::NodeHandle &nh, std::string &name) : nh(nh), name(name) {}
-	MainNode::MainNode() {}
-	MainNode::~MainNode() {}
-	void MainNode::onInit()
-	{
-		NODELET_INFO("MainNode::onInit -- START");
-		logEnabled = nh.advertise<logEnabledMsg>("logEnabled", 5);
-	  environmentData = nh.subscribe("environmentData", 1, &MainNode::environmentDataCallback, this);
+MainNode::MainNode(ros::NodeHandle & nh, std::string & name)
+    : nh(nh)
+      , name(name)
+      , platoonControllerThread(platoonControllerRun)
+{}
+
+MainNode::MainNode()
+    : platoonControllerThread(platoonControllerRun)
+{}
+
+MainNode::~MainNode()
+{}
+
+void MainNode::onInit()
+{
+    NODELET_INFO("MainNode::onInit -- START");
+    logEnabled = nh.advertise<logEnabledMsg>("logEnabled", 5);
+    environmentData = nh.subscribe("environmentData", 1, &MainNode::environmentDataCallback, this);
     std::cout << "MainNode &nh: " << &nh << "\n";
 
+    // CODE GOES HERE
 
-    		// CODE GOES HERE
-		NODELET_INFO("MainNode::onInit -- END");
-	}
-  
-  void MainNode::environmentDataCallback(const environmentDataMsg::ConstPtr& inMsg)
-  {
+    NODELET_INFO("MainNode::onInit -- END");
+}
+
+void MainNode::environmentDataCallback(const environmentDataMsg::ConstPtr & inMsg)
+{
     std::cout << "MainNode recived new environmentData data (" << inMsg->distance << ", " << inMsg->prevSpeed << ").\n";
-  }
+}
 }