18 #include <sensor_msgs/TimeReference.h> 29 #include <Poco/Process.h> 30 #include <Poco/Pipe.h> 31 #include <Poco/PipeStream.h> 32 #include <Poco/Format.h> 33 #include <Poco/StreamCopier.h> 69 const int get_flags = 0666;
73 ROS_FATAL(
"SHM shmget(0x%08lx, %zd, %o) fail: %s",
83 void *p = shmat(shmid, 0, 0);
84 if (p == (
void *) -1) {
85 ROS_FATAL(
"SHM shmat(%d, 0, 0) fail: %s", shmid, strerror(errno));
90 return (
volatile struct shmTime*) p;
99 if (shmdt((
const void*) *shm) == -1)
100 ROS_FATAL(
"SHM shmdt(%p) fail: %s", *shm, strerror(errno));
124 asm volatile (
"" : : :
"memory");
127 static void time_ref_cb(
const sensor_msgs::TimeReference::ConstPtr &time_ref)
130 ROS_FATAL(
"Got time_ref before shm opens.");
156 time_ref->source.c_str(),
157 (
long unsigned) time_ref->time_ref.sec,
158 (
long unsigned) time_ref->time_ref.nsec);
169 const double stamp = time_ref->time_ref.toSec();
171 ROS_INFO(
"Setting system date to: %f", stamp);
174 Poco::Pipe outp, errp;
175 Poco::Process::Args args;
176 args.push_back(
"-n");
177 args.push_back(
"date");
178 args.push_back(
"-u");
179 args.push_back(
"-s");
180 args.push_back(Poco::format(
"@%f", stamp));
181 Poco::ProcessHandle ph = Poco::Process::launch(
"sudo", args, 0, &outp, &errp);
184 Poco::PipeInputStream outs(outp), errs(errp);
185 std::string out, err;
187 Poco::StreamCopier::copyToString(outs, out, 4096);
188 Poco::StreamCopier::copyToString(errs, err, 4096);
191 ROS_INFO(
"The system date is set.");
196 ROS_ERROR(
"Setting system date failed.");
203 int main(
int argc,
char *argv[])
211 std::string time_ref_topic;
217 nh.
param(
"shm_unit", shm_unit, 2);
219 nh.
param<std::string>(
"time_ref_topic", time_ref_topic,
"time_ref");
223 ROS_INFO_STREAM(
"NTP date fixup: " << ((
g_set_date) ?
"enabled" :
"disabled"));
232 .unreliable().maxDatagramSize(1024)
233 .reliable().tcpNoDelay(
true));
unsigned clockTimeStampNSec
#define ROS_DEBUG_THROTTLE(rate,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void put_shmTime(volatile struct shmTime **shm)
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
time_t receiveTimeStampSec
unsigned receiveTimeStampNSec
static volatile struct shmTime * get_shmTime(int unit)
int main(int argc, char *argv[])
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const long int NTPD_SHM_BASE
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void shutdown()
static void memory_barrier(void)
static void sig_handler(int sig)
static void time_ref_cb(const sensor_msgs::TimeReference::ConstPtr &time_ref)
#define ROS_ERROR_STREAM(args)
volatile struct shmTime * g_shm