diff --git a/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h b/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h
index 885116c100b7af2b44d1fd821f430007083da854..c3d75a8793ea19b108d34ef066ae62d03ec80f3a 100644
--- a/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h
+++ b/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h
@@ -5,6 +5,7 @@
 #include <ros/ros.h>
 #include "boost/thread.hpp"
 #include "USS_SRF02.h"
+#include <thread>
 
 namespace car
 {
@@ -20,7 +21,7 @@ namespace car
 			ros::NodeHandle nh_;
 			std::string name_;
 			ros::Publisher ussData;
-      boost::thread main;
+      std::thread main;
 	};
 }
 #endif
diff --git a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp
index a97965e4204b46164ac29ebb01be46426343a5b3..78324b61fae298ecc4e813af810fc7af56ac78c1 100644
--- a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp
+++ b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp
@@ -23,14 +23,14 @@ void Ultrasonic::onInit()
 {
     NODELET_INFO("Ultrasonic::onInit -- START");
     ussData = nh_.advertise<ussDataMsg>("ussData", 1);
-    main = boost::thread(
-        [this]()
+    main = std::thread(
+        [this]
         {
             for (;;)
             {
                 ussDataMsg msg;
                 auto distance = getDistance();
-                std::cout << "distance: " << distance << "\n";
+                NODELET_INFO("distance: %d\n", distance);
                 msg.distance = distance;
                 ussData.publish(msg);
             }