00001 #ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_H 00002 #define __RTT_ROSCLOCK_RTT_ROSCLOCK_H 00003 00004 #include <rtt/RTT.hpp> 00005 #include <rtt/os/TimeService.hpp> 00006 #include <ros/time.h> 00007 00008 namespace rtt_rosclock { 00009 00029 const ros::Time host_now(); 00030 00034 const ros::Time host_wall_now(); 00035 00040 const ros::Time rtt_now(); 00041 00047 const ros::Time rtt_wall_now(); 00048 00050 const RTT::Seconds host_offset_from_rtt(); 00051 00053 const bool set_sim_clock_activity(RTT::TaskContext *t); 00054 00056 void use_ros_clock_topic(); 00057 00059 void use_manual_clock(); 00060 00062 const bool enable_sim(); 00063 00065 const bool disable_sim(); 00066 00068 void update_sim_clock(const ros::Time new_time); 00069 } 00070 00071 #endif // ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_H