#include <rtt_rosclock_sim_clock_thread.h>
Public Types | |
enum | SimClockSource { SIM_CLOCK_SOURCE_MANUAL = 0, SIM_CLOCK_SOURCE_ROS_CLOCK_TOPIC = 1 } |
Simulation clock sources. More... | |
Public Member Functions | |
bool | setClockSource (SimClockSource clock_source) |
Set the simulation clock source by ID (see ClockSource enum) | |
bool | simTimeEnabled () const |
Check if simulation time is enabled. | |
bool | updateClock (const ros::Time new_time) |
bool | useManualClock () |
Set the clock source to use a manual source, i.e. call `updateClock()` manually. | |
bool | useROSClockTopic () |
Set the clock source to use the ROS /clock topic. | |
virtual | ~SimClockThread () |
Static Public Member Functions | |
static boost::shared_ptr < SimClockThread > | GetInstance () |
Get an instance to the singleton SimClockThread or NULL. | |
static boost::shared_ptr < SimClockThread > | Instance () |
Get an instance to the singleton SimClockThread or create one. | |
static void | Release () |
Release the singleton SimClockThread. | |
Protected Member Functions | |
virtual bool | breakLoop () |
void | clockMsgCallback (const rosgraph_msgs::ClockConstPtr &clock) |
ROS message callback for /clock topic. | |
virtual void | finalize () |
virtual bool | initialize () |
virtual void | loop () |
void | operator= (SimClockThread const &) |
void | resetTimeService () |
Re-set the RTT::os::TimeService to zero and restart logging. | |
SimClockThread () | |
Constructor is protected, use Instance() to create and get a singleton. | |
SimClockThread (SimClockThread const &) | |
bool | updateClockInternal (const ros::Time new_time) |
Update the RTT clock and SimClockActivities with a new time (see updateClock() for manually updating) | |
Protected Attributes | |
ros::CallbackQueue | callback_queue_ |
Custom callback queue used in this thread. | |
SimClockSource | clock_source_ |
Current clock source. | |
ros::Subscriber | clock_subscriber_ |
ROS /clock topic subscriber. | |
ros::NodeHandle | nh_ |
ROS NodeHandle for communication. | |
bool | process_callbacks_ |
Keep running the thread loop if this is set to true. | |
RTT::os::TimeService * | time_service_ |
Convenient pointer to RTT time service. | |
Static Protected Attributes | |
static boost::shared_ptr < SimClockThread > | singleton |
SimClockThread singleton. |
This activity subscribes to the ROS /clock topic and overrides the RTT TimeService if the `/use_sim_time` ROS parameter is set.
Definition at line 60 of file rtt_rosclock_sim_clock_thread.h.
Simulation clock sources.
Definition at line 73 of file rtt_rosclock_sim_clock_thread.h.
SimClockThread::~SimClockThread | ( | ) | [virtual] |
Definition at line 96 of file rtt_rosclock_sim_clock_thread.cpp.
SimClockThread::SimClockThread | ( | ) | [protected] |
Constructor is protected, use Instance() to create and get a singleton.
Definition at line 88 of file rtt_rosclock_sim_clock_thread.cpp.
rtt_rosclock::SimClockThread::SimClockThread | ( | SimClockThread const & | ) | [protected] |
bool SimClockThread::breakLoop | ( | ) | [protected, virtual] |
Reimplemented from RTT::os::Thread.
Definition at line 281 of file rtt_rosclock_sim_clock_thread.cpp.
void SimClockThread::clockMsgCallback | ( | const rosgraph_msgs::ClockConstPtr & | clock | ) | [protected] |
ROS message callback for /clock topic.
Definition at line 130 of file rtt_rosclock_sim_clock_thread.cpp.
void SimClockThread::finalize | ( | ) | [protected, virtual] |
Reimplemented from RTT::os::Thread.
Definition at line 287 of file rtt_rosclock_sim_clock_thread.cpp.
boost::shared_ptr< SimClockThread > SimClockThread::GetInstance | ( | ) | [static] |
Get an instance to the singleton SimClockThread or NULL.
Definition at line 62 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::initialize | ( | ) | [protected, virtual] |
Reimplemented from RTT::os::Thread.
Definition at line 214 of file rtt_rosclock_sim_clock_thread.cpp.
boost::shared_ptr< SimClockThread > SimClockThread::Instance | ( | ) | [static] |
Get an instance to the singleton SimClockThread or create one.
Definition at line 67 of file rtt_rosclock_sim_clock_thread.cpp.
void SimClockThread::loop | ( | ) | [protected, virtual] |
Reimplemented from RTT::os::Thread.
Definition at line 271 of file rtt_rosclock_sim_clock_thread.cpp.
void rtt_rosclock::SimClockThread::operator= | ( | SimClockThread const & | ) | [protected] |
void SimClockThread::Release | ( | ) | [static] |
Release the singleton SimClockThread.
Definition at line 79 of file rtt_rosclock_sim_clock_thread.cpp.
void SimClockThread::resetTimeService | ( | ) | [protected] |
Re-set the RTT::os::TimeService to zero and restart logging.
Definition at line 191 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::setClockSource | ( | SimClockSource | clock_source | ) |
Set the simulation clock source by ID (see ClockSource enum)
Definition at line 101 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::simTimeEnabled | ( | ) | const |
Check if simulation time is enabled.
Definition at line 125 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::updateClock | ( | const ros::Time | new_time | ) |
Update the RTT clock and SimClockActivities with a new time
This can be called internally from clockMsgCallback or externally by another library (e.g. Gazebo) for in-process triggering. This can be called manually via the ros.clock global service's updateSimClock() operation.
Definition at line 136 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::updateClockInternal | ( | const ros::Time | new_time | ) | [protected] |
Update the RTT clock and SimClockActivities with a new time (see updateClock() for manually updating)
Definition at line 146 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::useManualClock | ( | ) |
Set the clock source to use a manual source, i.e. call `updateClock()` manually.
Definition at line 120 of file rtt_rosclock_sim_clock_thread.cpp.
bool SimClockThread::useROSClockTopic | ( | ) |
Set the clock source to use the ROS /clock topic.
Definition at line 115 of file rtt_rosclock_sim_clock_thread.cpp.
Custom callback queue used in this thread.
Definition at line 134 of file rtt_rosclock_sim_clock_thread.h.
Current clock source.
Definition at line 124 of file rtt_rosclock_sim_clock_thread.h.
ROS /clock topic subscriber.
Definition at line 132 of file rtt_rosclock_sim_clock_thread.h.
ros::NodeHandle rtt_rosclock::SimClockThread::nh_ [protected] |
ROS NodeHandle for communication.
Definition at line 130 of file rtt_rosclock_sim_clock_thread.h.
bool rtt_rosclock::SimClockThread::process_callbacks_ [protected] |
Keep running the thread loop if this is set to true.
Definition at line 127 of file rtt_rosclock_sim_clock_thread.h.
boost::shared_ptr< SimClockThread > SimClockThread::singleton [static, protected] |
SimClockThread singleton.
Definition at line 106 of file rtt_rosclock_sim_clock_thread.h.
Convenient pointer to RTT time service.
Definition at line 121 of file rtt_rosclock_sim_clock_thread.h.