#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) More... | |
| bool | simTimeEnabled () const |
| Check if simulation time is enabled. More... | |
| bool | updateClock (const ros::Time new_time) |
| bool | useManualClock () |
Set the clock source to use a manual source, i.e. call updateClock() manually. More... | |
| bool | useROSClockTopic () |
| Set the clock source to use the ROS /clock topic. More... | |
| virtual | ~SimClockThread () |
Public Member Functions inherited from RTT::os::Thread | |
| virtual unsigned | getCpuAffinity () const |
| virtual int | getMaxOverrun () const |
| virtual const char * | getName () const |
| void | getPeriod (secs &s, nsecs &ns) const |
| virtual Seconds | getPeriod () const |
| virtual nsecs | getPeriodNS () const |
| virtual unsigned int | getPid () const |
| virtual int | getPriority () const |
| virtual int | getScheduler () const |
| Seconds | getStopTimeout () const |
| virtual RTOS_TASK * | getTask () |
| virtual const RTOS_TASK * | getTask () const |
| virtual bool | isActive () const |
| virtual bool | isPeriodic () const |
| virtual bool | isRunning () const |
| virtual bool | setCpuAffinity (unsigned cpu_affinity) |
| virtual void | setMaxOverrun (int m) |
| bool | setPeriod (Seconds s) |
| bool | setPeriod (TIME_SPEC p) |
| bool | setPeriod (secs s, nsecs ns) |
| virtual bool | setPriority (int priority) |
| virtual bool | setScheduler (int sched_type) |
| void | setStopTimeout (Seconds s) |
| virtual void | setWaitPeriodPolicy (int p) |
| virtual bool | start () |
| virtual bool | stop () |
| Thread (int scheduler, int priority, double period, unsigned cpu_affinity, const std::string &name) | |
| virtual void | yield () |
| virtual | ~Thread () |
Public Member Functions inherited from RTT::os::ThreadInterface | |
| bool | isSelf () const |
| ThreadInterface () | |
| unsigned int | threadNumber () const |
| virtual | ~ThreadInterface () |
Static Public Member Functions | |
| static boost::shared_ptr< SimClockThread > | GetInstance () |
| Get an instance to the singleton SimClockThread or NULL. More... | |
| static boost::shared_ptr< SimClockThread > | Instance () |
| Get an instance to the singleton SimClockThread or create one. More... | |
| static void | Release () |
| Release the singleton SimClockThread. More... | |
Static Public Member Functions inherited from RTT::os::Thread | |
| static void | setLockTimeoutNoPeriod (double timeout_in_s) |
| static void | setLockTimeoutPeriodFactor (double factor) |
| static void | setStackSize (unsigned int ssize) |
Protected Member Functions | |
| virtual bool | breakLoop () |
| void | clockMsgCallback (const rosgraph_msgs::ClockConstPtr &clock) |
| ROS message callback for /clock topic. More... | |
| 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. More... | |
| SimClockThread () | |
| Constructor is protected, use Instance() to create and get a singleton. More... | |
| 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) More... | |
Protected Member Functions inherited from RTT::os::Thread | |
| void | emergencyStop () |
| virtual void | step () |
| void | terminate () |
Protected Attributes | |
| ros::CallbackQueue | callback_queue_ |
| Custom callback queue used in this thread. More... | |
| SimClockSource | clock_source_ |
| Current clock source. More... | |
| ros::Subscriber | clock_subscriber_ |
| ROS /clock topic subscriber. More... | |
| ros::NodeHandle | nh_ |
| ROS NodeHandle for communication. More... | |
| bool | process_callbacks_ |
| Keep running the thread loop if this is set to true. More... | |
| RTT::os::TimeService * | time_service_ |
| Convenient pointer to RTT time service. More... | |
Protected Attributes inherited from RTT::os::Thread | |
| bool | active |
| MutexRecursive | breaker |
| bool | inloop |
| int | maxOverRun |
| int | msched_type |
| NANO_TIME | period |
| bool | prepareForExit |
| RTOS_TASK | rtos_task |
| bool | running |
| rt_sem_t | sem |
| double | stopTimeout |
Protected Attributes inherited from RTT::os::ThreadInterface | |
| int | threadnb |
Static Protected Attributes | |
| static boost::shared_ptr< SimClockThread > | singleton |
| SimClockThread singleton. More... | |
Static Protected Attributes inherited from RTT::os::Thread | |
| static unsigned int | default_stack_size |
| static double | lock_timeout_no_period_in_s |
| static double | lock_timeout_period_factor |
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.
| Enumerator | |
|---|---|
| SIM_CLOCK_SOURCE_MANUAL | |
| SIM_CLOCK_SOURCE_ROS_CLOCK_TOPIC | |
Definition at line 73 of file rtt_rosclock_sim_clock_thread.h.
|
virtual |
Definition at line 96 of file rtt_rosclock_sim_clock_thread.cpp.
|
protected |
Constructor is protected, use Instance() to create and get a singleton.
Definition at line 88 of file rtt_rosclock_sim_clock_thread.cpp.
|
protected |
|
protectedvirtual |
Reimplemented from RTT::os::Thread.
Definition at line 281 of file rtt_rosclock_sim_clock_thread.cpp.
|
protected |
ROS message callback for /clock topic.
Definition at line 130 of file rtt_rosclock_sim_clock_thread.cpp.
|
protectedvirtual |
Reimplemented from RTT::os::Thread.
Definition at line 287 of file rtt_rosclock_sim_clock_thread.cpp.
|
static |
Get an instance to the singleton SimClockThread or NULL.
Definition at line 62 of file rtt_rosclock_sim_clock_thread.cpp.
|
protectedvirtual |
Reimplemented from RTT::os::Thread.
Definition at line 214 of file rtt_rosclock_sim_clock_thread.cpp.
|
static |
Get an instance to the singleton SimClockThread or create one.
Definition at line 67 of file rtt_rosclock_sim_clock_thread.cpp.
|
protectedvirtual |
Reimplemented from RTT::os::Thread.
Definition at line 271 of file rtt_rosclock_sim_clock_thread.cpp.
|
protected |
|
static |
Release the singleton SimClockThread.
Definition at line 79 of file rtt_rosclock_sim_clock_thread.cpp.
|
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.
|
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.
|
protected |
Custom callback queue used in this thread.
Definition at line 134 of file rtt_rosclock_sim_clock_thread.h.
|
protected |
Current clock source.
Definition at line 124 of file rtt_rosclock_sim_clock_thread.h.
|
protected |
ROS /clock topic subscriber.
Definition at line 132 of file rtt_rosclock_sim_clock_thread.h.
|
protected |
ROS NodeHandle for communication.
Definition at line 130 of file rtt_rosclock_sim_clock_thread.h.
|
protected |
Keep running the thread loop if this is set to true.
Definition at line 127 of file rtt_rosclock_sim_clock_thread.h.
|
staticprotected |
SimClockThread singleton.
Definition at line 106 of file rtt_rosclock_sim_clock_thread.h.
|
protected |
Convenient pointer to RTT time service.
Definition at line 121 of file rtt_rosclock_sim_clock_thread.h.