Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
rtt_rosclock::SimClockThread Class Reference

#include <rtt_rosclock_sim_clock_thread.h>

Inheritance diagram for rtt_rosclock::SimClockThread:
Inheritance graph
[legend]

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_TASKgetTask ()
 
virtual const RTOS_TASKgetTask () 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< SimClockThreadGetInstance ()
 Get an instance to the singleton SimClockThread or NULL. More...
 
static boost::shared_ptr< SimClockThreadInstance ()
 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...
 
bool process_callbacks_
 Keep running the thread loop if this is set to true. More...
 
RTT::os::TimeServicetime_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< SimClockThreadsingleton
 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
 

Detailed Description

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 53 of file rtt_rosclock_sim_clock_thread.h.

Member Enumeration Documentation

Simulation clock sources.

Enumerator
SIM_CLOCK_SOURCE_MANUAL 
SIM_CLOCK_SOURCE_ROS_CLOCK_TOPIC 

Definition at line 66 of file rtt_rosclock_sim_clock_thread.h.

Constructor & Destructor Documentation

SimClockThread::~SimClockThread ( )
virtual

Definition at line 89 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 81 of file rtt_rosclock_sim_clock_thread.cpp.

rtt_rosclock::SimClockThread::SimClockThread ( SimClockThread const &  )
protected

Member Function Documentation

bool SimClockThread::breakLoop ( )
protectedvirtual

Reimplemented from RTT::os::Thread.

Definition at line 276 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 123 of file rtt_rosclock_sim_clock_thread.cpp.

void SimClockThread::finalize ( )
protectedvirtual

Reimplemented from RTT::os::Thread.

Definition at line 282 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 55 of file rtt_rosclock_sim_clock_thread.cpp.

bool SimClockThread::initialize ( )
protectedvirtual

Reimplemented from RTT::os::Thread.

Definition at line 207 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 60 of file rtt_rosclock_sim_clock_thread.cpp.

void SimClockThread::loop ( )
protectedvirtual

Reimplemented from RTT::os::Thread.

Definition at line 266 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 72 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 184 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 94 of file rtt_rosclock_sim_clock_thread.cpp.

bool SimClockThread::simTimeEnabled ( ) const

Check if simulation time is enabled.

Definition at line 118 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 129 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 139 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 113 of file rtt_rosclock_sim_clock_thread.cpp.

bool SimClockThread::useROSClockTopic ( )

Set the clock source to use the ROS /clock topic.

Definition at line 108 of file rtt_rosclock_sim_clock_thread.cpp.

Member Data Documentation

ros::CallbackQueue rtt_rosclock::SimClockThread::callback_queue_
protected

Custom callback queue used in this thread.

Definition at line 125 of file rtt_rosclock_sim_clock_thread.h.

SimClockSource rtt_rosclock::SimClockThread::clock_source_
protected

Current clock source.

Definition at line 117 of file rtt_rosclock_sim_clock_thread.h.

ros::Subscriber rtt_rosclock::SimClockThread::clock_subscriber_
protected

ROS /clock topic subscriber.

Definition at line 123 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 120 of file rtt_rosclock_sim_clock_thread.h.

boost::shared_ptr< SimClockThread > SimClockThread::singleton
staticprotected

SimClockThread singleton.

Definition at line 99 of file rtt_rosclock_sim_clock_thread.h.

RTT::os::TimeService* rtt_rosclock::SimClockThread::time_service_
protected

Convenient pointer to RTT time service.

Definition at line 114 of file rtt_rosclock_sim_clock_thread.h.


The documentation for this class was generated from the following files:


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