00001
00015 #include <ros/ros.h>
00016 #include <ros/console.h>
00017
00018 #include <sensor_msgs/TimeReference.h>
00019
00020 #include <sys/ipc.h>
00021 #include <sys/shm.h>
00022
00023 #include <signal.h>
00024 #include <cstring>
00025 #include <cerrno>
00026
00027
00028
00029 #include <Poco/Process.h>
00030 #include <Poco/Pipe.h>
00031 #include <Poco/PipeStream.h>
00032 #include <Poco/Format.h>
00033 #include <Poco/StreamCopier.h>
00034
00036 struct shmTime
00037 {
00038 int mode;
00039
00040
00041
00042
00043
00044
00045
00046 volatile int count;
00047 time_t clockTimeStampSec;
00048 int clockTimeStampUSec;
00049 time_t receiveTimeStampSec;
00050 int receiveTimeStampUSec;
00051 int leap;
00052 int precision;
00053 int nsamples;
00054 volatile int valid;
00055 unsigned clockTimeStampNSec;
00056 unsigned receiveTimeStampNSec;
00057 int dummy[8];
00058 };
00059
00060 const long int NTPD_SHM_BASE = 0x4e545030;
00061
00066 static volatile struct shmTime *get_shmTime(int unit)
00067 {
00068
00069 const int get_flags = 0666;
00070
00071 int shmid = shmget(NTPD_SHM_BASE + unit, sizeof(shmTime), get_flags);
00072 if (shmid < 0) {
00073 ROS_FATAL("SHM shmget(0x%08lx, %zd, %o) fail: %s",
00074 NTPD_SHM_BASE + unit,
00075 sizeof(shmTime),
00076 get_flags,
00077 strerror(errno));
00078 return NULL;
00079 }
00080
00081
00082
00083 void *p = shmat(shmid, 0, 0);
00084 if (p == (void *) -1) {
00085 ROS_FATAL("SHM shmat(%d, 0, 0) fail: %s", shmid, strerror(errno));
00086 return NULL;
00087 }
00088
00089 ROS_INFO("SHM(%d) key 0x%08lx, successfully opened", unit, NTPD_SHM_BASE + unit);
00090 return (volatile struct shmTime*) p;
00091 }
00092
00093 static void put_shmTime(volatile struct shmTime **shm)
00094 {
00095 ROS_ASSERT(shm != NULL);
00096 if (*shm == NULL)
00097 return;
00098
00099 if (shmdt((const void*) *shm) == -1)
00100 ROS_FATAL("SHM shmdt(%p) fail: %s", *shm, strerror(errno));
00101 else
00102 *shm = NULL;
00103 }
00104
00105
00107 volatile struct shmTime *g_shm = NULL;
00108 static bool g_set_date = false;
00109
00110 static void sig_handler(int sig)
00111 {
00112 put_shmTime(&g_shm);
00113 ros::shutdown();
00114 }
00115
00122 static inline void memory_barrier(void)
00123 {
00124 asm volatile ("" : : : "memory");
00125 }
00126
00127 static void time_ref_cb(const sensor_msgs::TimeReference::ConstPtr &time_ref)
00128 {
00129 if (g_shm == NULL) {
00130 ROS_FATAL("Got time_ref before shm opens.");
00131 ros::shutdown();
00132 }
00133
00134
00135 g_shm->mode = 1;
00136 g_shm->nsamples = 3;
00137
00138 g_shm->valid = 0;
00139 g_shm->count += 1;
00140
00141 memory_barrier();
00142 g_shm->clockTimeStampSec = time_ref->time_ref.sec;
00143 g_shm->clockTimeStampUSec = time_ref->time_ref.nsec / 1000;
00144 g_shm->clockTimeStampNSec = time_ref->time_ref.nsec;
00145 g_shm->receiveTimeStampSec = time_ref->header.stamp.sec;
00146 g_shm->receiveTimeStampUSec = time_ref->header.stamp.nsec / 1000;
00147 g_shm->receiveTimeStampNSec = time_ref->header.stamp.nsec;
00148 g_shm->leap = 0;
00149 g_shm->precision = -1;
00150 memory_barrier();
00151
00152 g_shm->count += 1;
00153 g_shm->valid = 1;
00154
00155 ROS_DEBUG_THROTTLE(10, "Got time_ref: %s: %lu.%09lu",
00156 time_ref->source.c_str(),
00157 (long unsigned) time_ref->time_ref.sec,
00158 (long unsigned) time_ref->time_ref.nsec);
00159
00160
00161
00162
00163
00164
00165
00166
00167 if (g_set_date && ros::Time::now().sec < 1234567890ULL) {
00168
00169 const double stamp = time_ref->time_ref.toSec();
00170
00171 ROS_INFO("Setting system date to: %f", stamp);
00172
00173
00174 Poco::Pipe outp, errp;
00175 Poco::Process::Args args;
00176 args.push_back("-n");
00177 args.push_back("date");
00178 args.push_back("-u");
00179 args.push_back("-s");
00180 args.push_back(Poco::format("@%f", stamp));
00181 Poco::ProcessHandle ph = Poco::Process::launch("sudo", args, 0, &outp, &errp);
00182
00183 int rc = ph.wait();
00184 Poco::PipeInputStream outs(outp), errs(errp);
00185 std::string out, err;
00186
00187 Poco::StreamCopier::copyToString(outs, out, 4096);
00188 Poco::StreamCopier::copyToString(errs, err, 4096);
00189
00190 if (rc == 0) {
00191 ROS_INFO("The system date is set.");
00192 ROS_DEBUG_STREAM("OUT: " << out);
00193 ROS_DEBUG_STREAM("ERR: " << err);
00194 }
00195 else {
00196 ROS_ERROR("Setting system date failed.");
00197 ROS_ERROR_STREAM("OUT: " << out);
00198 ROS_ERROR_STREAM("ERR: " << err);
00199 }
00200 }
00201 }
00202
00203 int main(int argc, char *argv[])
00204 {
00205 ros::init(argc, argv, "ntpd_shm");
00206
00207 ros::NodeHandle nh("~");
00208 ros::Subscriber time_ref_sub;
00209
00210 int shm_unit;
00211 std::string time_ref_topic;
00212
00213
00214 signal(SIGINT, sig_handler);
00215
00216
00217 nh.param("shm_unit", shm_unit, 2);
00218 nh.param("fixup_date", g_set_date, false);
00219 nh.param<std::string>("time_ref_topic", time_ref_topic, "time_ref");
00220
00221
00222 ROS_INFO_STREAM("NTP time source: " << ros::names::resolve(time_ref_topic, true));
00223 ROS_INFO_STREAM("NTP date fixup: " << ((g_set_date) ? "enabled" : "disabled"));
00224
00225 g_shm = get_shmTime(shm_unit);
00226 if (g_shm == NULL)
00227 return 1;
00228
00229
00230 time_ref_sub = nh.subscribe(time_ref_topic, 10, time_ref_cb,
00231 ros::TransportHints()
00232 .unreliable().maxDatagramSize(1024)
00233 .reliable().tcpNoDelay(true));
00234
00235 ros::spin();
00236 put_shmTime(&g_shm);
00237 return 0;
00238 }