An abstraction for a periodic thread. More...
#include <yarp/os/PeriodicThread.h>
Inherited by AnalogWrapper, audioFromFileDevice, AudioPlayerWrapper, AudioRecorderWrapper [private]
, BatteryWrapper, BoschIMU, ControlBoardWrapper, DiagnosticThread, FakeAnalogSensor, FakeBattery, fakeIMU, FakeLaser, fakeLocalizerThread, fakeMicrophone, FakeMotionControl, fakeNavigationThread, fakeSpeaker, FrameTransformClient, FrameTransformServer, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, JoypadControlServer, JoypadControlWatchdog, LaserFromDepth, LaserFromExternalPort, LaserFromPointCloud, LaserFromRosTopic, laserHokuyo, Localization2DServer, MonitorTrigger, MultipleAnalogSensorsServer, navigation2DServer, Nop, PriorityDebugThread, Rangefinder2DWrapper, RGBDSensorWrapper, RpLidar, RpLidar2, ServerGrabber, TextureBattery, ThreadedTimer, TimerSingleton, V4L_camera, yarp::dev::IJoypadEventDriven [private]
, yarp::dev::OVRHeadset, yarp::manager::ConcurentRateWrapper, yarp::manager::YarpBroker, yarp::os::RateThread [private]
, yarp::os::RateThreadWrapper, and yarp::os::SystemRateThread.
Classes | |
class | Private |
Public Member Functions | |
PeriodicThread (double period, ShouldUseSystemClock useSystemClock=ShouldUseSystemClock::No) | |
Constructor. More... | |
virtual | ~PeriodicThread () |
bool | start () |
Call this to start the thread. More... | |
void | step () |
Call this to "step" the thread rather than starting it. More... | |
void | stop () |
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called). More... | |
void | askToStop () |
Stop the thread. More... | |
bool | isRunning () const |
Returns true when the thread is started, false otherwise. More... | |
bool | isSuspended () const |
Returns true when the thread is suspended, false otherwise. More... | |
bool | setPeriod (double period) |
Set the (new) period of the thread. More... | |
double | getPeriod () const |
Return the current period of the thread. More... | |
void | suspend () |
Suspend the thread, the thread keeps running by doLoop is never executed. More... | |
void | resume () |
Resume the thread if previously suspended. More... | |
void | resetStat () |
Reset thread statistics. More... | |
double | getEstimatedPeriod () const |
Return estimated period since last reset. More... | |
void | getEstimatedPeriod (double &av, double &std) const |
Return estimated period since last reset. More... | |
unsigned int | getIterations () const |
Return the number of iterations performed since last reset. More... | |
double | getEstimatedUsed () const |
Return the estimated duration of the run() function since last reset. More... | |
void | getEstimatedUsed (double &av, double &std) const |
Return estimated duration of the run() function since last reset. More... | |
int | setPriority (int priority, int policy=-1) |
Set the priority and scheduling policy of the thread, if the OS supports that. More... | |
int | getPriority () const |
Query the current priority of the thread, if the OS supports that. More... | |
int | getPolicy () const |
Query the current scheduling policy of the thread, if the OS supports that. More... | |
Protected Member Functions | |
virtual bool | threadInit () |
Initialization method. More... | |
virtual void | threadRelease () |
Release method. More... | |
virtual void | run ()=0 |
Loop function. More... | |
virtual void | beforeStart () |
Called just before a new thread starts. More... | |
virtual void | afterStart (bool success) |
Called just after a new thread starts (or fails to start), this is executed by the same thread that calls start(). More... | |
An abstraction for a periodic thread.
Definition at line 24 of file PeriodicThread.h.
|
explicit |
Constructor.
Thread begins in a dormant state. Call PeriodicThread::start to get things going.
period | The period in seconds [sec] between successive calls to the PeriodicThread::run method (remember you need to call PeriodicThread::start first before anything happens) |
useSystemClock | whether the thread should always use the system clock, or depend on the current configuration of the network. |
Definition at line 271 of file PeriodicThread.cpp.
|
virtual |
Definition at line 276 of file PeriodicThread.cpp.
|
protectedvirtual |
Called just after a new thread starts (or fails to start), this is executed by the same thread that calls start().
success | true iff the new thread started successfully. |
Reimplemented in yarp::os::RateThreadWrapper, and yarp::os::RateThread.
Definition at line 374 of file PeriodicThread.cpp.
void PeriodicThread::askToStop | ( | ) |
Stop the thread.
Like stop but it does not call join, safe to be called from run().
Definition at line 301 of file PeriodicThread.cpp.
|
protectedvirtual |
Called just before a new thread starts.
This method is executed by the same thread that calls start().
Reimplemented in yarp::os::RateThreadWrapper, and yarp::os::RateThread.
Definition at line 370 of file PeriodicThread.cpp.
double PeriodicThread::getEstimatedPeriod | ( | ) | const |
Return estimated period since last reset.
Definition at line 336 of file PeriodicThread.cpp.
void PeriodicThread::getEstimatedPeriod | ( | double & | av, |
double & | std | ||
) | const |
Return estimated period since last reset.
[out] | av | average value |
[out] | std | standard deviation |
Definition at line 346 of file PeriodicThread.cpp.
double PeriodicThread::getEstimatedUsed | ( | ) | const |
Return the estimated duration of the run() function since last reset.
Definition at line 341 of file PeriodicThread.cpp.
void PeriodicThread::getEstimatedUsed | ( | double & | av, |
double & | std | ||
) | const |
Return estimated duration of the run() function since last reset.
[out] | av | average value |
[out] | std | standard deviation |
Definition at line 351 of file PeriodicThread.cpp.
unsigned int PeriodicThread::getIterations | ( | ) | const |
Return the number of iterations performed since last reset.
Definition at line 331 of file PeriodicThread.cpp.
double PeriodicThread::getPeriod | ( | ) | const |
Return the current period of the thread.
Definition at line 286 of file PeriodicThread.cpp.
int PeriodicThread::getPolicy | ( | ) | const |
Query the current scheduling policy of the thread, if the OS supports that.
Definition at line 389 of file PeriodicThread.cpp.
int PeriodicThread::getPriority | ( | ) | const |
Query the current priority of the thread, if the OS supports that.
Definition at line 384 of file PeriodicThread.cpp.
bool PeriodicThread::isRunning | ( | ) | const |
Returns true when the thread is started, false otherwise.
Definition at line 316 of file PeriodicThread.cpp.
bool PeriodicThread::isSuspended | ( | ) | const |
Returns true when the thread is suspended, false otherwise.
Definition at line 291 of file PeriodicThread.cpp.
void PeriodicThread::resetStat | ( | ) |
Reset thread statistics.
Definition at line 356 of file PeriodicThread.cpp.
void PeriodicThread::resume | ( | ) |
Resume the thread if previously suspended.
Definition at line 326 of file PeriodicThread.cpp.
|
protectedpure virtual |
Loop function.
This is the thread itself. The thread calls the run() function every <period> ms. At the end of each run, the thread will sleep the amounth of time required, taking into account the time spent inside the loop function. Example: requested period is 10ms, the run() function take 3ms to be executed, the thread will sleep for 7ms.
Note: after each run is completed, the thread will call a yield() in order to facilitate other threads to run.
Implemented in yarp::os::RateThread, yarp::dev::IJoypadEventDriven, yarp::os::RateThreadWrapper, yarp::manager::YarpBroker, yarp::manager::ConcurentRateWrapper, FrameTransformServer, FrameTransformClient, Nop, ServerGrabber, RpLidar2, RpLidar, RGBDSensorWrapper, DiagnosticThread, Rangefinder2DWrapper, navigation2DServer, MultipleAnalogSensorsServer, WrenchStampedRosPublisher, TemperatureRosPublisher, PoseStampedRosPublisher, MagneticFieldRosPublisher, IMURosPublisher, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, Localization2DServer, laserHokuyo, LaserFromRosTopic, LaserFromPointCloud, LaserFromExternalPort, LaserFromDepth, JoypadControlServer, JoypadControlWatchdog, BoschIMU, fakeNavigationThread, FakeMotionControl, fakeLocalizerThread, FakeLaser, FakeBattery, FakeAnalogSensor, ControlBoardWrapper, BatteryWrapper, AudioRecorderWrapper, AudioPlayerWrapper, AnalogWrapper, PriorityDebugThread, MonitorTrigger, TextureBattery, and yarp::dev::OVRHeadset.
bool PeriodicThread::setPeriod | ( | double | period | ) |
Set the (new) period of the thread.
period | the period [sec] |
Definition at line 281 of file PeriodicThread.cpp.
int PeriodicThread::setPriority | ( | int | priority, |
int | policy = -1 |
||
) |
Set the priority and scheduling policy of the thread, if the OS supports that.
priority | the new priority of the thread. |
policy | the scheduling policy of the thread |
Definition at line 379 of file PeriodicThread.cpp.
bool PeriodicThread::start | ( | ) |
Call this to start the thread.
Blocks until initThread() is executed.
Definition at line 311 of file PeriodicThread.cpp.
void PeriodicThread::step | ( | ) |
Call this to "step" the thread rather than starting it.
This will execute at most one call to doLoop before returning.
Definition at line 306 of file PeriodicThread.cpp.
void PeriodicThread::stop | ( | ) |
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called).
Actually calls join. This will deadlock if called from run(), use askToStop() instead.
Definition at line 296 of file PeriodicThread.cpp.
void PeriodicThread::suspend | ( | ) |
Suspend the thread, the thread keeps running by doLoop is never executed.
Definition at line 321 of file PeriodicThread.cpp.
|
protectedvirtual |
Initialization method.
The thread executes this function when it starts and before "run". This is a good place to perform initialization tasks that need to be done by the thread itself (device drivers initialization, memory allocation etc). If the function returns false the thread quits and never calls "run". The return value of threadInit() is notified to the class and passed as a parameter to afterStart(). Note that afterStart() is called by the same thread that is executing the "start" method.
Reimplemented in yarp::dev::IJoypadEventDriven, yarp::os::RateThreadWrapper, yarp::os::RateThread, yarp::manager::YarpBroker, FrameTransformServer, FrameTransformClient, ServerGrabber, RpLidar2, RpLidar, RGBDSensorWrapper, Rangefinder2DWrapper, laserHokuyo, LaserFromRosTopic, LaserFromPointCloud, LaserFromExternalPort, LaserFromDepth, JoypadControlServer, BoschIMU, fakeNavigationThread, FakeMotionControl, fakeLocalizerThread, FakeLaser, FakeAnalogSensor, BatteryWrapper, AudioRecorderWrapper, AudioPlayerWrapper, AnalogWrapper, PriorityDebugThread, and yarp::dev::OVRHeadset.
Definition at line 361 of file PeriodicThread.cpp.
|
protectedvirtual |
Release method.
The thread executes this function once when it exits, after the last "run". This is a good place to release resources that were initialized in threadInit() (release memory, and device driver resources).
Reimplemented in yarp::os::RateThreadWrapper, yarp::os::RateThread, yarp::manager::YarpBroker, FrameTransformServer, FrameTransformClient, ServerGrabber, RpLidar2, RpLidar, RGBDSensorWrapper, Rangefinder2DWrapper, MultipleAnalogSensorsServer, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, laserHokuyo, LaserFromRosTopic, LaserFromPointCloud, LaserFromExternalPort, LaserFromDepth, JoypadControlServer, BoschIMU, fakeNavigationThread, FakeMotionControl, fakeLocalizerThread, FakeLaser, FakeAnalogSensor, BatteryWrapper, AudioRecorderWrapper, AudioPlayerWrapper, AnalogWrapper, PriorityDebugThread, and yarp::dev::OVRHeadset.
Definition at line 366 of file PeriodicThread.cpp.