YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
yarp::os::Thread Class Referenceabstract

An abstraction for a thread of execution. More...

#include <yarp/os/Thread.h>

Inherited by yarp::os::TypedReaderThread< yarp::os::Bottle >, yarp::os::TypedReaderThread< yarp::sig::ImageOf< yarp::sig::PixelFloat > >, yarp::os::TypedReaderThread< return_getAllTransforms >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::TypedReaderThread< ImageType >, yarp::os::TypedReaderThread< yarp::sig::Vector >, yarp::os::TypedReaderThread< yarp::sig::Sound >, yarp::os::TypedReaderThread< yarp::dev::LaserScan2D >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::TypedReaderThread< yarp::sig::FlexImage >, yarp::os::TypedReaderThread< SensorStreamingData >, yarp::os::TypedReaderThread< yarp::dev::impl::jointData >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::TypedReaderThread< yarp::dev::MobileBaseVelocity >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::TypedReaderThread< yarp::rosmsg::geometry_msgs::Twist >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::Image >, yarp::os::TypedReaderThread< yarp::sig::VectorOf >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::TypedReaderThread< yarp::os::PortablePair >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::TypedReaderThread< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::TypedReaderThread< ROS_MSG >, yarp::os::TypedReaderThread< VectorOf< unsigned char > >, yarp::os::TypedReaderThread< JoyData >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::TypedReaderThread< yarp::dev::Nav2D::Map2DLocation >, yarp::os::TypedReaderThread< yarp::dev::OdometryData >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::TypedReaderThread< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::TypedReaderThread< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::TypedReaderThread< yarp::rosmsg::sensor_msgs::PointCloud2 >, yarp::os::TypedReaderThread< DepthImage >, FakeBot, FakeFrameGrabber, Map2D_nws_ros2, MpiControlThread, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, RFModuleRespondHandler, RFModuleThreadedHandler, Ros2Spinner, RunReadWrite, RunTerminator, SegFault, SerialPort_nws_yarp, SpeechSynthesizer_nws_yarp, SpeechTranscription_nws_yarp, VirtualAnalogWrapper, ZombieHunterThread, streamThread, yarp::manager::ConcurentWrapper, yarp::manager::LocalBroker, yarp::os::RosNameSpace, yarp::os::Terminee, yarp::os::TypedReaderThread< T >, yarp::robotinterface::impl::CalibratorThread, and yarp::serversql::impl::ConnectThread.

Classes

class  Private
 

Public Member Functions

 Thread ()
 Constructor.
 
virtual ~Thread ()
 Destructor.
 
virtual void run ()=0
 Main body of the new thread.
 
virtual void onStop ()
 Call-back, called while halting the thread (before join).
 
bool start ()
 Start the new thread running.
 
bool stop ()
 Stop the thread.
 
virtual void beforeStart ()
 Called just before a new thread starts.
 
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().
 
virtual bool threadInit ()
 Initialization method.
 
virtual void threadRelease ()
 Release method.
 
bool isStopping ()
 Returns true if the thread is stopping (Thread::stop has been called).
 
bool isRunning ()
 Returns true if the thread is running (Thread::start has been called successfully and the thread has not stopped).
 
long int getKey ()
 Get a unique identifier for the thread.
 
int setPriority (int priority, int policy=-1)
 Set the priority and scheduling policy of the thread, if the OS supports that.
 
int getPriority ()
 Query the current priority of the thread, if the OS supports that.
 
int getPolicy ()
 Query the current scheduling policy of the thread, if the OS supports that.
 
bool join (double seconds=-1)
 The function returns when the thread execution has completed.
 
void setOptions (int stackSize=0)
 Set the stack size for the new thread.
 

Static Public Member Functions

static int getCount ()
 Check how many threads are running.
 
static long int getKeyOfCaller ()
 Get a unique identifier for the calling thread.
 
static void yield ()
 Reschedule the execution of current thread, allowing other threads to run.
 
static void setDefaultStackSize (int stackSize)
 Set the default stack size for all threads created after this point.
 

Detailed Description

An abstraction for a thread of execution.

Examples
os/threads/threads.cpp.

Definition at line 20 of file Thread.h.

Constructor & Destructor Documentation

◆ Thread()

Thread::Thread ( )

Constructor.

Thread begins in a dormant state. Call Thread::start to get things going.

Definition at line 65 of file Thread.cpp.

◆ ~Thread()

Thread::~Thread ( )
virtual

Destructor.

Definition at line 70 of file Thread.cpp.

Member Function Documentation

◆ afterStart()

void Thread::afterStart ( bool  success)
virtual

Called just after a new thread starts (or fails to start), this is executed by the same thread that calls start().

Parameters
successtrue iff the new thread started successfully.

Definition at line 114 of file Thread.cpp.

◆ beforeStart()

void Thread::beforeStart ( )
virtual

Called just before a new thread starts.

This method is executed by the same thread that calls start().

Definition at line 110 of file Thread.cpp.

◆ getCount()

int Thread::getCount ( )
static

Check how many threads are running.

Returns
the number of threads currently running

Definition at line 119 of file Thread.cpp.

◆ getKey()

long int Thread::getKey ( )

Get a unique identifier for the thread.

Returns
an identifier that is different for each thread within a process

Definition at line 125 of file Thread.cpp.

◆ getKeyOfCaller()

long int Thread::getKeyOfCaller ( )
static

Get a unique identifier for the calling thread.

Returns
an identifier for the calling thread

Definition at line 130 of file Thread.cpp.

◆ getPolicy()

int Thread::getPolicy ( )

Query the current scheduling policy of the thread, if the OS supports that.

Returns
the scheduling policy of the thread.

Definition at line 145 of file Thread.cpp.

◆ getPriority()

int Thread::getPriority ( )

Query the current priority of the thread, if the OS supports that.

Returns
the priority of the thread.

Definition at line 140 of file Thread.cpp.

◆ isRunning()

bool Thread::isRunning ( )

Returns true if the thread is running (Thread::start has been called successfully and the thread has not stopped).

Returns
true iff the thread is running

Definition at line 105 of file Thread.cpp.

◆ isStopping()

bool Thread::isStopping ( )

Returns true if the thread is stopping (Thread::stop has been called).

Returns
true iff the thread is stopping

Definition at line 99 of file Thread.cpp.

◆ join()

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.

Parameters
secondsthe maximum number of seconds to block the thread.
Returns
true if the thread execution is finished, false on time out.

Definition at line 76 of file Thread.cpp.

◆ onStop()

void Thread::onStop ( )
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 FakeFrameGrabber, yarp::os::Terminee, yarp::os::TypedReaderThread< T >, yarp::os::TypedReaderThread< DepthImage >, yarp::os::TypedReaderThread< ImageType >, yarp::os::TypedReaderThread< JoyData >, yarp::os::TypedReaderThread< return_getAllTransforms >, yarp::os::TypedReaderThread< ROS_MSG >, yarp::os::TypedReaderThread< SensorStreamingData >, yarp::os::TypedReaderThread< VectorOf< unsigned char > >, yarp::os::TypedReaderThread< yarp::dev::impl::jointData >, yarp::os::TypedReaderThread< yarp::dev::LaserScan2D >, yarp::os::TypedReaderThread< yarp::dev::MobileBaseVelocity >, 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::Twist >, 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::PointCloud2 >, 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::Sound >, yarp::os::TypedReaderThread< yarp::sig::Vector >, yarp::os::TypedReaderThread< yarp::sig::VectorOf >, yarp::robotinterface::impl::CalibratorThread, and ZombieHunterThread.

Definition at line 88 of file Thread.cpp.

◆ run()

virtual void yarp::os::Thread::run ( )
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 Map2D_nws_ros2, Ros2Spinner, MpiControlThread, FakeBot, FakeFrameGrabber, streamThread, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, SerialPort_nws_yarp, SpeechSynthesizer_nws_yarp, SpeechTranscription_nws_yarp, SegFault, VirtualAnalogWrapper, yarp::manager::ConcurentWrapper, yarp::manager::LocalBroker, RFModuleRespondHandler, RFModuleThreadedHandler, yarp::os::RosNameSpace, yarp::os::Terminee, yarp::os::TypedReaderThread< T >, yarp::os::TypedReaderThread< DepthImage >, yarp::os::TypedReaderThread< ImageType >, yarp::os::TypedReaderThread< JoyData >, yarp::os::TypedReaderThread< return_getAllTransforms >, yarp::os::TypedReaderThread< ROS_MSG >, yarp::os::TypedReaderThread< SensorStreamingData >, yarp::os::TypedReaderThread< VectorOf< unsigned char > >, yarp::os::TypedReaderThread< yarp::dev::impl::jointData >, yarp::os::TypedReaderThread< yarp::dev::LaserScan2D >, yarp::os::TypedReaderThread< yarp::dev::MobileBaseVelocity >, 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::Twist >, 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::PointCloud2 >, 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::Sound >, yarp::os::TypedReaderThread< yarp::sig::Vector >, yarp::os::TypedReaderThread< yarp::sig::VectorOf >, yarp::robotinterface::impl::CalibratorThread, ZombieHunterThread, RunTerminator, RunReadWrite, and yarp::serversql::impl::ConnectThread.

◆ setDefaultStackSize()

static void yarp::os::Thread::setDefaultStackSize ( int  stackSize)
inlinestatic

Set the default stack size for all threads created after this point.

A value of 0 will use a reasonable default.

Parameters
stackSizethe desired stack size in bytes.

Definition at line 215 of file Thread.h.

◆ setOptions()

void yarp::os::Thread::setOptions ( int  stackSize = 0)
inline

Set the stack size for the new thread.

Must be called before Thread::start

Parameters
stackSizethe desired stack size in bytes (if 0, uses a reasonable default)
Deprecated:
since YARP 3.0.0

Definition at line 205 of file Thread.h.

◆ setPriority()

int Thread::setPriority ( int  priority,
int  policy = -1 
)

Set the priority and scheduling policy of the thread, if the OS supports that.

Parameters
prioritythe new priority of the thread.
policythe scheduling policy of the thread
Returns
-1 if the priority cannot be set.
Note
The thread policy is highly OS dependent and a right combination of priority and policy should be used. In some platform changing thread priorities is subject to having the right permission. For example, the following combinations are supported on most Linux platforms: SCHED_OTHER : policy=0, priority=[0 .. 0] SCHED_FIFO : policy=1, priority=[1 .. 99] SCHED_RR : policy=2, priority=[1 .. 99]

Definition at line 135 of file Thread.cpp.

◆ start()

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().

Returns
true iff the new thread starts successfully

Definition at line 93 of file Thread.cpp.

◆ stop()

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().

Returns
true iff the thread stops successfully

Definition at line 81 of file Thread.cpp.

◆ threadInit()

virtual bool yarp::os::Thread::threadInit ( )
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 MpiControlThread, streamThread, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, and yarp::manager::LocalBroker.

Definition at line 104 of file Thread.h.

◆ threadRelease()

virtual void yarp::os::Thread::threadRelease ( )
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 MpiControlThread, streamThread, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, and yarp::manager::LocalBroker.

Definition at line 115 of file Thread.h.

◆ yield()

void Thread::yield ( )
static

Reschedule the execution of current thread, allowing other threads to run.

Definition at line 150 of file Thread.cpp.


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