Go to the documentation of this file.00001
00037 #include "ros/ros.h"
00038 #include "rosgraph_msgs/Clock.h"
00039
00040 #include <sys/time.h>
00041
00042 #define SIM_TIME_INCREMENT_US 10000
00043
00044
00045
00046
00047
00048
00049
00050 int main(int argc, char **argv)
00051 {
00052 ros::init(argc, argv, "sim_time_source");
00053 ros::NodeHandle sim_time_node;
00054
00055
00056 int sim_speedup;
00057 ros::NodeHandle node_priv("~");
00058 node_priv.param<int>("sim_speedup", sim_speedup, 1);
00059
00060
00061 struct timeval start;
00062 int rv = gettimeofday(&start, NULL);
00063 usleep(1000);
00064 struct timeval now;
00065 rv = gettimeofday(&now, NULL);
00066 if (0 != rv)
00067 {
00068 ROS_ERROR("Invalid return from gettimeofday: %d", rv);
00069 return -1;
00070 }
00071
00072 rosgraph_msgs::Clock sim_time;
00073 sim_time.clock.sec = now.tv_sec - start.tv_sec;
00074 sim_time.clock.nsec = now.tv_usec * 1000;
00075 ros::Publisher sim_time_pub = sim_time_node.advertise<rosgraph_msgs::Clock>("clock", 1);
00076
00077 ROS_INFO("Starting simulation time publisher at time: %d.%d", sim_time.clock.sec, sim_time.clock.nsec);
00078
00079 while (ros::ok())
00080 {
00081 sim_time_pub.publish(sim_time);
00082
00083 sim_time.clock.nsec = sim_time.clock.nsec + SIM_TIME_INCREMENT_US * 1000;
00084 while (sim_time.clock.nsec > 1000000000)
00085 {
00086 sim_time.clock.nsec -= 1000000000;
00087 ++sim_time.clock.sec;
00088 }
00089
00090 usleep(SIM_TIME_INCREMENT_US / sim_speedup);
00091 ros::spinOnce();
00092 }
00093 }