Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes | Static Private Attributes | List of all members
RTT::extras::SimulationThread Class Reference

#include <SimulationThread.hpp>

Inheritance diagram for RTT::extras::SimulationThread:
Inheritance graph
[legend]

Public Member Functions

virtual bool isRunning () const
 
virtual bool run (unsigned int maxsteps)
 
virtual os::ThreadInterfacesimthread ()
 
virtual bool start ()
 
virtual bool start (unsigned int maxsteps)
 
virtual ~SimulationThread ()
 
- Public Member Functions inherited from RTT::extras::TimerThread
bool addActivity (PeriodicActivity *t)
 
bool removeActivity (PeriodicActivity *t)
 
 TimerThread (int priority, const std::string &name, double periodicity, unsigned cpu_affinity=~0)
 
 TimerThread (int scheduler, int priority, const std::string &name, double periodicity, unsigned cpu_affinity=~0)
 
virtual ~TimerThread ()
 
- 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 setCpuAffinity (unsigned cpu_affinity)
 
virtual void setMaxOverrun (int m)
 
bool setPeriod (Seconds s)
 
bool setPeriod (secs s, nsecs ns)
 
bool setPeriod (TIME_SPEC p)
 
virtual bool setPriority (int priority)
 
virtual bool setScheduler (int sched_type)
 
void setStopTimeout (Seconds s)
 
virtual void setWaitPeriodPolicy (int p)
 
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 SimulationThreadPtr Instance (double period=0.001)
 
static bool Release ()
 
- Static Public Member Functions inherited from RTT::extras::TimerThread
static TimerThreadPtr Instance (int priority, double periodicity)
 
static TimerThreadPtr Instance (int scheduler, int priority, double periodicity)
 
static TimerThreadPtr Instance (int scheduler, int priority, double periodicity, unsigned cpu_affinity)
 
- 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

void finalize ()
 
bool initialize ()
 
 SimulationThread (double period)
 
void step ()
 
- Protected Member Functions inherited from RTT::extras::TimerThread
void reorderList ()
 
- Protected Member Functions inherited from RTT::os::Thread
virtual bool breakLoop ()
 
void emergencyStop ()
 
virtual void loop ()
 
void terminate ()
 

Private Attributes

os::TimeServicebeat
 
unsigned int cursteps
 
unsigned int maxsteps_
 
bool sim_running
 

Static Private Attributes

static SimulationThreadPtr _instance
 

Additional Inherited Members

- Static Public Attributes inherited from RTT::extras::TimerThread
static const unsigned int MAX_ACTIVITIES = 64
 
- Protected Types inherited from RTT::extras::TimerThread
typedef std::vector< boost::weak_ptr< TimerThread > > TimerThreadList
 
- Protected Attributes inherited from RTT::extras::TimerThread
os::MutexRecursive mutex
 
- 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 inherited from RTT::extras::TimerThread
static TimerThreadList TimerThreads
 
- Static Protected Attributes inherited from RTT::os::Thread
static unsigned int default_stack_size = 0
 
static double lock_timeout_no_period_in_s = 1.0
 
static double lock_timeout_period_factor = 10.0
 

Detailed Description

This thread is the simulated real-time periodic thread in the Orocos system.

All your activities in the same program must be a SimulationActivity for this to work, since the os::TimeService global time is updated when this thread runs.

By default, the update period is 0.001 seconds. If you want to run with a finer or coarser grained time step, use the Instance() method and supply another period before SimulationActivities are created.

Note
This implementation has lost the capability to run SimulationActivity objects of different periods.

Definition at line 64 of file SimulationThread.hpp.

Constructor & Destructor Documentation

RTT::SimulationThread::~SimulationThread ( )
virtual

Destructor

Definition at line 98 of file SimulationThread.cpp.

RTT::SimulationThread::SimulationThread ( double  period)
protected

Constructor

Definition at line 86 of file SimulationThread.cpp.

Member Function Documentation

void RTT::SimulationThread::finalize ( )
protectedvirtual
See also
base::RunnableInterface::finalize()

Reimplemented from RTT::extras::TimerThread.

Definition at line 155 of file SimulationThread.cpp.

bool RTT::SimulationThread::initialize ( )
protectedvirtual
See also
base::RunnableInterface::initialize()

Reimplemented from RTT::extras::TimerThread.

Definition at line 141 of file SimulationThread.cpp.

SimulationThreadPtr RTT::SimulationThread::Instance ( double  period = 0.001)
static

Create the SimulationThread with a given period. Only one SimulationThread can be created.

Parameters
periodThe period in seconds at which the simulation takes steps and updates the TimeService. Only the first invocation of Instance will consider this parameter. The others will ignore it.

Definition at line 69 of file SimulationThread.cpp.

bool RTT::SimulationThread::isRunning ( ) const
virtual

Returns true if thread is running or run( unsigned int ) is being invoked.

Reimplemented from RTT::os::Thread.

Definition at line 103 of file SimulationThread.cpp.

bool RTT::SimulationThread::Release ( )
static

Releases the SimulationThread Reference counting might aid in making this call safe

Returns
true on success, false on failure

Definition at line 79 of file SimulationThread.cpp.

bool RTT::SimulationThread::run ( unsigned int  maxsteps)
virtual

Execute maxsteps steps immediately. This function will call the step() functions maxsteps times, without requiring start() or stop() to be called before or after. The thread is thus not used.

Returns
false if maxsteps == 0
Postcondition
When run() returns, step() has been called maxsteps times.

Definition at line 122 of file SimulationThread.cpp.

os::ThreadInterface * RTT::SimulationThread::simthread ( )
virtual

Always returns the MainThread.

Definition at line 137 of file SimulationThread.cpp.

bool RTT::SimulationThread::start ( )
virtual

Start the Thread.

Postcondition
initialize() is called first
The Thread is running
Returns
true if the function did succeed. false otherwise.

Reimplemented from RTT::os::Thread.

Definition at line 108 of file SimulationThread.cpp.

bool RTT::SimulationThread::start ( unsigned int  maxsteps)
virtual

Only run the simulation maxsteps time steps, then stop the SimulationThread.

Returns
false if maxsteps == 0 or if thread could not be started.

Definition at line 114 of file SimulationThread.cpp.

void RTT::SimulationThread::step ( )
protectedvirtual
See also
base::RunnableInterface::step()

Reimplemented from RTT::extras::TimerThread.

Definition at line 166 of file SimulationThread.cpp.

Member Data Documentation

SimulationThreadPtr RTT::SimulationThread::_instance
staticprivate

Our only instance of the SimulationThread

Definition at line 135 of file SimulationThread.hpp.

os::TimeService* RTT::extras::SimulationThread::beat
private

The System clock.

Definition at line 140 of file SimulationThread.hpp.

unsigned int RTT::extras::SimulationThread::cursteps
private

Definition at line 142 of file SimulationThread.hpp.

unsigned int RTT::extras::SimulationThread::maxsteps_
private

Definition at line 142 of file SimulationThread.hpp.

bool RTT::extras::SimulationThread::sim_running
private

Definition at line 144 of file SimulationThread.hpp.


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


rtt
Author(s): RTT Developers
autogenerated on Fri Oct 25 2019 03:59:46