An abstraction for a thread of execution. More...
#include <yarp/os/Thread.h>
Inherited by FakeBot, MpiControlThread, PlayStreamThread, PortAudioRecorderDeviceDriver, RFModuleRespondHandler, RFModuleThreadedHandler, RunReadWrite, RunTerminator, SegFault, ServerInertial [private]
, ServerSerial [private]
, ServerSoundGrabber [private]
, streamThread, yarp::os::TypedReaderThread< DepthImage >, yarp::os::TypedReaderThread< ImageType >, yarp::os::TypedReaderThread< JoyData >, yarp::os::TypedReaderThread< ROS_MSG >, yarp::os::TypedReaderThread< SensorStreamingData >, yarp::os::TypedReaderThread< yarp::dev::impl::jointData >, yarp::os::TypedReaderThread< yarp::dev::LaserScan2D >, yarp::os::TypedReaderThread< yarp::dev::Nav2D::Map2DLocation >, yarp::os::TypedReaderThread< yarp::dev::OdometryData >, yarp::os::TypedReaderThread< yarp::os::Bottle >, yarp::os::TypedReaderThread< yarp::os::PortablePair >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Image >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::TypedReaderThread< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::TypedReaderThread< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::TypedReaderThread< yarp::sig::FlexImage >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelFloat > >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelRgb > >, yarp::os::TypedReaderThread< yarp::sig::Sound >, yarp::os::TypedReaderThread< yarp::sig::Vector >, yarp::os::TypedReaderThread< yarp::sig::VectorOf >, VirtualAnalogWrapper, yarp::manager::ConcurentWrapper, yarp::manager::LocalBroker, yarp::os::RosNameSpace, yarp::os::Terminee, yarp::os::TypedReaderThread< T >, yarp::serversql::impl::ConnectThread, and ZombieHunterThread.
Classes | |
class | Private |
Public Member Functions | |
Thread () | |
Constructor. More... | |
virtual | ~Thread () |
Destructor. More... | |
virtual void | run ()=0 |
Main body of the new thread. More... | |
virtual void | onStop () |
Call-back, called while halting the thread (before join). More... | |
bool | start () |
Start the new thread running. More... | |
bool | stop () |
Stop the thread. 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... | |
virtual bool | threadInit () |
Initialization method. More... | |
virtual void | threadRelease () |
Release method. More... | |
bool | isStopping () |
Returns true if the thread is stopping (Thread::stop has been called). More... | |
bool | isRunning () |
Returns true if the thread is running (Thread::start has been called successfully and the thread has not stopped). More... | |
long int | getKey () |
Get a unique identifier for the thread. 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 () |
Query the current priority of the thread, if the OS supports that. More... | |
int | getPolicy () |
Query the current scheduling policy of the thread, if the OS supports that. More... | |
bool | join (double seconds=-1) |
The function returns when the thread execution has completed. More... | |
void | setOptions (int stackSize=0) |
Set the stack size for the new thread. More... | |
Static Public Member Functions | |
static int | getCount () |
Check how many threads are running. More... | |
static long int | getKeyOfCaller () |
Get a unique identifier for the calling thread. More... | |
static void | yield () |
Reschedule the execution of current thread, allowing other threads to run. More... | |
static void | setDefaultStackSize (int stackSize) |
Set the default stack size for all threads created after this point. More... | |
An abstraction for a thread of execution.
Thread::Thread | ( | ) |
Constructor.
Thread begins in a dormant state. Call Thread::start to get things going.
Definition at line 68 of file Thread.cpp.
|
virtual |
Destructor.
Definition at line 73 of file Thread.cpp.
|
virtual |
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. |
Definition at line 117 of file Thread.cpp.
|
virtual |
Called just before a new thread starts.
This method is executed by the same thread that calls start().
Definition at line 113 of file Thread.cpp.
|
static |
Check how many threads are running.
Definition at line 122 of file Thread.cpp.
long int Thread::getKey | ( | ) |
Get a unique identifier for the thread.
Definition at line 128 of file Thread.cpp.
|
static |
Get a unique identifier for the calling thread.
Definition at line 133 of file Thread.cpp.
int Thread::getPolicy | ( | ) |
Query the current scheduling policy of the thread, if the OS supports that.
Definition at line 148 of file Thread.cpp.
int Thread::getPriority | ( | ) |
Query the current priority of the thread, if the OS supports that.
Definition at line 143 of file Thread.cpp.
bool Thread::isRunning | ( | ) |
Returns true if the thread is running (Thread::start has been called successfully and the thread has not stopped).
Definition at line 108 of file Thread.cpp.
bool Thread::isStopping | ( | ) |
Returns true if the thread is stopping (Thread::stop has been called).
Definition at line 102 of file Thread.cpp.
bool Thread::join | ( | double | seconds = -1 | ) |
The function returns when the thread execution has completed.
Stops the execution of the thread that calls this function until either the thread to join has finished execution (when it returns from run()) or after seconds seconds.
seconds | the maximum number of seconds to block the thread. |
Definition at line 79 of file Thread.cpp.
|
virtual |
Call-back, called while halting the thread (before join).
This callback is executed by the same thread that calls stop(). It should not be called directly. Override this method to do the right thing for your particular Thread::run.
Reimplemented in ZombieHunterThread, yarp::os::TypedReaderThread< T >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::TypedReaderThread< yarp::sig::Vector >, yarp::os::TypedReaderThread< ImageType >, yarp::os::TypedReaderThread< yarp::sig::VectorOf >, yarp::os::TypedReaderThread< yarp::dev::impl::jointData >, yarp::os::TypedReaderThread< SensorStreamingData >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelFloat > >, yarp::os::TypedReaderThread< yarp::os::Bottle >, yarp::os::TypedReaderThread< ROS_MSG >, yarp::os::TypedReaderThread< yarp::os::PortablePair >, yarp::os::TypedReaderThread< JoyData >, yarp::os::TypedReaderThread< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::TypedReaderThread< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelRgb > >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::TypedReaderThread< yarp::dev::Nav2D::Map2DLocation >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::TypedReaderThread< yarp::dev::LaserScan2D >, yarp::os::TypedReaderThread< yarp::sig::FlexImage >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::TypedReaderThread< yarp::dev::OdometryData >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::TypedReaderThread< DepthImage >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Image >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::TypedReaderThread< yarp::sig::Sound >, and yarp::os::Terminee.
Definition at line 91 of file Thread.cpp.
|
pure virtual |
Main body of the new thread.
Override this method to do what you want. After Thread::start is called, this method will start running in a separate thread. It is important that this method either keeps checking Thread::isStopping to see if it should stop, or you override the Thread::onStop method to interact with it in some way to shut the new thread down. There is no really reliable, portable way to stop a thread cleanly unless that thread cooperates.
Implemented in yarp::serversql::impl::ConnectThread, RunReadWrite, RunTerminator, ZombieHunterThread, yarp::os::TypedReaderThread< T >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::TypedReaderThread< yarp::sig::Vector >, yarp::os::TypedReaderThread< ImageType >, yarp::os::TypedReaderThread< yarp::sig::VectorOf >, yarp::os::TypedReaderThread< yarp::dev::impl::jointData >, yarp::os::TypedReaderThread< SensorStreamingData >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelFloat > >, yarp::os::TypedReaderThread< yarp::os::Bottle >, yarp::os::TypedReaderThread< ROS_MSG >, yarp::os::TypedReaderThread< yarp::os::PortablePair >, yarp::os::TypedReaderThread< JoyData >, yarp::os::TypedReaderThread< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::TypedReaderThread< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelRgb > >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::TypedReaderThread< yarp::dev::Nav2D::Map2DLocation >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::TypedReaderThread< yarp::dev::LaserScan2D >, yarp::os::TypedReaderThread< yarp::sig::FlexImage >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::TypedReaderThread< yarp::dev::OdometryData >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::TypedReaderThread< DepthImage >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Image >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::TypedReaderThread< yarp::sig::Sound >, yarp::os::Terminee, yarp::os::RosNameSpace, RFModuleThreadedHandler, RFModuleRespondHandler, yarp::manager::LocalBroker, yarp::manager::ConcurentWrapper, VirtualAnalogWrapper, SegFault, ServerSoundGrabber, ServerSerial, ServerInertial, PortAudioRecorderDeviceDriver, PlayStreamThread, streamThread, FakeBot, and MpiControlThread.
|
inlinestatic |
|
inline |
Set the stack size for the new thread.
Must be called before Thread::start
stackSize | the desired stack size in bytes (if 0, uses a reasonable default) |
int Thread::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 138 of file Thread.cpp.
bool Thread::start | ( | ) |
Start the new thread running.
The new thread will call the user-defined Thread::run method. The function starts the thread and waits until the thread executes threadInit(). If the initialization was not successful the thread exits, otherwise run is executed. The return value of threadInit() is passed to afterStart().
Definition at line 96 of file Thread.cpp.
bool Thread::stop | ( | ) |
Stop the thread.
Thread::isStopping will start returning true. The user-defined Thread::onStop method will be called. Then, this simply sits back and waits. Wait for thread termination so cannot be called from within run().
Definition at line 84 of file Thread.cpp.
|
inlinevirtual |
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::manager::LocalBroker, PortAudioRecorderDeviceDriver, PlayStreamThread, streamThread, and MpiControlThread.
|
inlinevirtual |
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::manager::LocalBroker, PortAudioRecorderDeviceDriver, PlayStreamThread, streamThread, and MpiControlThread.
|
static |
Reschedule the execution of current thread, allowing other threads to run.
Definition at line 153 of file Thread.cpp.