rtt_rosclock.h
Go to the documentation of this file.
1 #ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_H
2 #define __RTT_ROSCLOCK_RTT_ROSCLOCK_H
3 
4 #include <rtt/RTT.hpp>
5 #include <rtt/os/TimeService.hpp>
6 #include <ros/time.h>
7 
8 namespace rtt_rosclock {
9 
29  const ros::Time host_now();
30 
34  const ros::Time host_wall_now();
35 
40  const ros::Time rtt_now();
41 
47  const ros::Time rtt_wall_now();
48 
51 
54 
56  void use_ros_clock_topic();
57 
59  void use_manual_clock();
60 
62  const bool enable_sim();
63 
65  const bool disable_sim();
66 
68  void update_sim_clock(const ros::Time new_time);
69 }
70 
71 #endif // ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_H
double Seconds
const bool enable_sim()
Use a simulated clock source.
const RTT::Seconds host_offset_from_rtt()
Get the difference in seconds between rtt_wall_now() and host_wall_now()
const ros::Time host_wall_now()
Get the current time according to CLOCK_HOST_REALTIME or the wall time.
void use_manual_clock()
Use manual clock updates.
void use_ros_clock_topic()
Use ROS /clock topic for time measurement.
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.
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.
const ros::Time rtt_now()
Get the current time according to RTT.


rtt_rosclock
Author(s):
autogenerated on Sat Jun 8 2019 18:06:00