41 #ifndef __RTT_ROSCLOCK_SIM_CLOCK_THREAD_H 42 #define __RTT_ROSCLOCK_SIM_CLOCK_THREAD_H 52 #include <rosgraph_msgs/Clock.h> 141 #endif // ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_ACTIVITY_H bool useManualClock()
Set the clock source to use a manual source, i.e. call updateClock() manually.
bool updateClockInternal(const ros::Time new_time)
Update the RTT clock and SimClockActivities with a new time (see updateClock() for manually updating)...
void operator=(SimClockThread const &)
virtual bool initialize()
void resetTimeService()
Re-set the RTT::os::TimeService to zero and restart logging.
static boost::shared_ptr< SimClockThread > GetInstance()
Get an instance to the singleton SimClockThread or NULL.
bool useROSClockTopic()
Set the clock source to use the ROS /clock topic.
SimClockSource
Simulation clock sources.
ros::Subscriber clock_subscriber_
ROS /clock topic subscriber.
ros::NodeHandle nh_
ROS NodeHandle for communication.
static boost::shared_ptr< SimClockThread > Instance()
Get an instance to the singleton SimClockThread or create one.
static void Release()
Release the singleton SimClockThread.
bool updateClock(const ros::Time new_time)
virtual ~SimClockThread()
ros::CallbackQueue callback_queue_
Custom callback queue used in this thread.
void clockMsgCallback(const rosgraph_msgs::ClockConstPtr &clock)
ROS message callback for /clock topic.
bool simTimeEnabled() const
Check if simulation time is enabled.
static boost::shared_ptr< SimClockThread > singleton
SimClockThread singleton.
bool setClockSource(SimClockSource clock_source)
Set the simulation clock source by ID (see ClockSource enum)
bool process_callbacks_
Keep running the thread loop if this is set to true.
SimClockThread()
Constructor is protected, use Instance() to create and get a singleton.
RTT::os::TimeService * time_service_
Convenient pointer to RTT time service.
SimClockSource clock_source_
Current clock source.