diff --git a/source/RobotAPI/components/units/RobotUnit/util/RtTiming.h b/source/RobotAPI/components/units/RobotUnit/util/RtTiming.h
index 4e88ef1f3a8fae9e6baeeb453aa4711a40d77f30..837bda2321d9961953f45d59c225b534c8b51ea7 100644
--- a/source/RobotAPI/components/units/RobotUnit/util/RtTiming.h
+++ b/source/RobotAPI/components/units/RobotUnit/util/RtTiming.h
@@ -29,13 +29,13 @@
 
 namespace armarx
 {
+
     inline IceUtil::Time
     rtNow()
     {
-        return IceUtil::Time::now(IceUtil::Time::Monotonic);
-        //        using namespace std::chrono;
-        //        auto epoch = time_point_cast<microseconds>(high_resolution_clock::now()).time_since_epoch();
-        //        return IceUtil::Time::microSeconds(duration_cast<milliseconds>(epoch).count());
+        struct timespec ts;
+        clock_gettime(CLOCK_MONOTONIC, &ts);
+        return IceUtil::Time::microSeconds(ts.tv_sec * 1e6 + ts.tv_nsec / 1000);
     }
 } // namespace armarx
 
@@ -43,9 +43,8 @@ namespace armarx
 //! \ingroup VirtualTime
 //! Prints duration with comment in front of it, yet only once per second.
 #define RT_TIMING_END_COMMENT(name, comment)                                                       \
-    ARMARX_RT_LOGF_INFO("%s - duration: %.3f ms",                                                  \
-                        comment,                                                                   \
-                        IceUtil::Time(armarx::rtNow() - name).toMilliSecondsDouble())              \
+    ARMARX_RT_LOGF_INFO(                                                                           \
+        "%s - duration: %.3f ms", comment, (armarx::rtNow() - name).toMilliSecondsDouble())        \
         .deactivateSpam(1);
 //! \ingroup VirtualTime
 //! Prints duration
@@ -53,7 +52,7 @@ namespace armarx
 //! \ingroup VirtualTime
 //! Prints duration with comment in front of it if it took longer than threshold
 #define RT_TIMING_CEND_COMMENT(name, comment, thresholdMs)                                         \
-    if ((armarx::rtNow() - name).toMilliSecondsDouble() >= thresholdMs)                            \
+    if ((armarx::rtNow() - name).toMicroSeconds() >= thresholdMs)                                  \
     RT_TIMING_END_COMMENT(name, comment)
 //! \ingroup VirtualTime
 //! Prints duration if it took longer than thresholdMs