rtt_rosclock.cpp
Go to the documentation of this file.
1 
2 #include <time.h>
3 #include <rtt/RTT.hpp>
4 
8 
9 namespace rtt_rosclock {
11 }
12 
14 {
15  if(SimClockThread::GetInstance() && SimClockThread::GetInstance()->simTimeEnabled()) {
16  return rtt_now();
17  }
18 
19  #ifdef __XENO__
20  // Use Xenomai 2.6 feature to get the NTP-synched real-time clock
21  timespec ts = {0,0};
22  int ret = clock_gettime(CLOCK_HOST_REALTIME, &ts);
23  if(ret) {
24  RTT::log(RTT::Error) << "Could not query CLOCK_HOST_REALTIME (" << CLOCK_HOST_REALTIME <<"): "<< errno << RTT::endlog();
25  return rtt_rosclock::rtt_now();
26  }
27 
28  return ros::Time(ts.tv_sec, ts.tv_nsec);
29  #else
30  return ros::Time::now();
31  #endif
32 }
33 
35 {
36  #ifdef __XENO__
37  // Use Xenomai 2.6 feature to get the NTP-synched real-time clock
38  timespec ts = {0,0};
39  int ret = clock_gettime(CLOCK_HOST_REALTIME, &ts);
40  if(ret) {
41  RTT::log(RTT::Error) << "Could not query CLOCK_HOST_REALTIME (" << CLOCK_HOST_REALTIME <<"): "<< errno << RTT::endlog();
43  }
44 
45  return ros::Time(ts.tv_sec, ts.tv_nsec);
46  #else
48  return ros::Time(now.sec, now.nsec);
49  #endif
50 }
51 
53 {
54  // count the zeros... -987654321--
55  const uint64_t one_E9 = 1000000000ULL;
56  // NOTE: getNSecs returns wall time, getTicks returns offset time
58  uint32_t sec32_part = nsec64 / one_E9;
59  uint32_t nsec32_part = nsec64 % one_E9;
60  //RTT::log(RTT::Error) << "sec: " << sec32_part << " nsec: " << nsec32_part << RTT::endlog();
61  return ros::Time(sec32_part, nsec32_part);
62 }
63 
65 {
66  const uint64_t one_E9 = 1000000000ll;
67  // NOTE: getNSecs returns wall time, getTicks returns offset time
68  uint64_t nsec64 = RTT::os::TimeService::Instance()->getNSecs();
69  uint64_t sec64_part = nsec64 / one_E9;
70  uint64_t nsec64_part = nsec64 % one_E9;
71  //RTT::log(RTT::Error) << "sec: " << sec32 << " nsec: " << nsec32 << RTT::endlog();
72  return ros::Time(sec64_part, nsec64_part);
73 }
74 
76 {
78 }
79 
81 {
82  SimClockThread::Instance()->useROSClockTopic();
83 }
84 
86 {
87  SimClockThread::Instance()->useManualClock();
88 }
89 
91 {
92  if (!t) return false;
93  return t->setActivity(new SimClockActivity(t->getPeriod()));
94 }
95 
97 {
98  return SimClockThread::Instance()->start();
99 }
100 
102 {
103  return SimClockThread::Instance()->stop();
104 }
105 
107 {
108  SimClockThread::Instance()->updateClock(new_time);
109 }
double Seconds
const bool enable_sim()
Use a simulated clock source.
static nsecs ticks2nsecs(const ticks t)
const RTT::Seconds host_offset_from_rtt()
Get the difference in seconds between rtt_wall_now() and host_wall_now()
nsecs getNSecs() const
const ros::Time host_wall_now()
Get the current time according to CLOCK_HOST_REALTIME or the wall time.
static boost::shared_ptr< SimClockThread > GetInstance()
Get an instance to the singleton SimClockThread or NULL.
static TimeService * Instance()
bool setActivity(base::ActivityInterface *new_act)
virtual Seconds getPeriod() const
boost::shared_ptr< rtt_rosclock::SimClockThread > sim_clock_thread
void use_manual_clock()
Use manual clock updates.
void use_ros_clock_topic()
Use ROS /clock topic for time measurement.
static boost::shared_ptr< SimClockThread > Instance()
Get an instance to the singleton SimClockThread or create one.
const bool set_sim_clock_activity(RTT::TaskContext *t)
Set a TaskContext to use a periodic simulation clock activity.
const ros::Time rtt_wall_now()
Get the current wall time according to RTT.
void update_sim_clock(const ros::Time new_time)
Update the current simulation time and trigger all simulated TaskContexts.
static WallTime now()
const bool disable_sim()
Do&#39;t use a simulated clock source.
const ros::Time host_now()
Get the current time according to CLOCK_HOST_REALTIME or the simulation time.
static Time now()
const ros::Time rtt_now()
Get the current time according to RTT.
static Logger & log()
static Logger::LogFunction endlog()


rtt_rosclock
Author(s):
autogenerated on Mon May 10 2021 02:45:33