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

#include <FileDescriptorActivity.hpp>

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

Public Member Functions

virtual bool breakLoop ()
 
void clearAllWatches ()
 
 FileDescriptorActivity (int priority, base::RunnableInterface *_r=0, const std::string &name="FileDescriptorActivity")
 
 FileDescriptorActivity (int scheduler, int priority, base::RunnableInterface *_r=0, const std::string &name="FileDescriptorActivity")
 
 FileDescriptorActivity (int scheduler, int priority, Seconds period, base::RunnableInterface *_r=0, const std::string &name="FileDescriptorActivity")
 
 FileDescriptorActivity (int scheduler, int priority, Seconds period, unsigned cpu_affinity, base::RunnableInterface *_r=0, const std::string &name="FileDescriptorActivity")
 
virtual Seconds getPeriod () const
 Get the intended period (not the actual running period) More...
 
int getTimeout () const
 
int getTimeout_us () const
 
bool hasError () const
 
bool hasTimeout () const
 
bool isRunning () const
 
bool isUpdated (int fd) const
 
bool isWatched (int fd) const
 
virtual void loop ()
 
virtual bool setPeriod (Seconds period)
 Set the intended period (not the actual running period) More...
 
void setTimeout (int timeout)
 
void setTimeout_us (int timeout_us)
 
virtual bool start ()
 
virtual void step ()
 
virtual bool stop ()
 
virtual bool timeout ()
 
virtual bool trigger ()
 
void unwatch (int fd)
 
void watch (int fd)
 
virtual void work (base::RunnableInterface::WorkReason reason)
 
virtual ~FileDescriptorActivity ()
 
- Public Member Functions inherited from RTT::extras::FileDescriptorActivityInterface
virtual ~FileDescriptorActivityInterface ()
 
- Public Member Functions inherited from RTT::Activity
 Activity (base::RunnableInterface *r=0, const std::string &name="Activity")
 Create a not real-time Activity. This creates a not real-time, non-periodic thread, with priority equal to RTT::os::LowestPriority. More...
 
 Activity (int priority, base::RunnableInterface *r=0, const std::string &name="Activity")
 Create a real-time Activity with a given priority. The thread is run in the ORO_SCHED_RT scheduler. More...
 
 Activity (int priority, Seconds period, base::RunnableInterface *r=0, const std::string &name="Activity")
 Create a real-time Activity with a given priority and period. The thread is run in the ORO_SCHED_RT scheduler. More...
 
 Activity (int scheduler, int priority, base::RunnableInterface *r=0, const std::string &name="Activity")
 Create an Activity with a given scheduler type and priority. More...
 
 Activity (int scheduler, int priority, Seconds period, base::RunnableInterface *r=0, const std::string &name="Activity")
 Create an Activity with a given scheduler type, priority and period. More...
 
 Activity (int scheduler, int priority, Seconds period, unsigned cpu_affinity, base::RunnableInterface *r=0, const std::string &name="Activity")
 Create an Activity with a given scheduler type, priority, period and cpu affinity. More...
 
virtual bool execute ()
 
virtual void finalize ()
 
virtual unsigned getCpuAffinity () const
 
virtual bool initialize ()
 
virtual bool isActive () const
 
virtual bool isPeriodic () const
 
virtual bool setCpuAffinity (unsigned cpu)
 
void setWaitPeriodPolicy (int p)
 
virtual os::ThreadInterfacethread ()
 
virtual ~Activity ()
 
- Public Member Functions inherited from RTT::base::ActivityInterface
 ActivityInterface ()
 
 ActivityInterface (RunnableInterface *run)
 
virtual RunnableInterfacegetRunner () const
 
virtual bool run (RunnableInterface *r)
 
virtual ~ActivityInterface ()
 
- Public Member Functions inherited from RTT::os::Thread
virtual int getMaxOverrun () const
 
virtual const char * getName () const
 
void getPeriod (secs &s, nsecs &ns) 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 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)
 
 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 ()
 

Private Member Functions

void triggerUpdateSets ()
 

Private Attributes

bool m_break_loop
 
RTT::os::Mutex m_command_mutex
 
fd_set m_fd_set
 
fd_set m_fd_work
 
bool m_has_error
 
bool m_has_timeout
 
int m_interrupt_pipe [2]
 
RTT::os::Mutex m_lock
 intended period More...
 
Seconds m_period
 timeout in microseconds More...
 
bool m_running
 
int m_timeout_us
 
bool m_trigger
 
bool m_update_sets
 
std::set< int > m_watched_fds
 

Static Private Attributes

static const char CMD_ANY_COMMAND = 0
 

Additional Inherited Members

- Public Types inherited from RTT::base::ActivityInterface
typedef boost::shared_ptr< ActivityInterfaceshared_ptr
 
- 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 inherited from RTT::base::ActivityInterface
void disableRun (RunnableInterface *caller)
 
- Protected Member Functions inherited from RTT::os::Thread
void emergencyStop ()
 
void terminate ()
 
- Protected Attributes inherited from RTT::Activity
os::Condition msg_cond
 
os::Mutex msg_lock
 
bool mstopRequested
 
bool mtimeout
 
int mwaitpolicy
 
double update_period
 
- Protected Attributes inherited from RTT::base::ActivityInterface
RunnableInterfacerunner
 
- 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::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

An activity which is triggered by the availability of data on a set of file descriptors. step() (and hence the base::RunnableInterface's step() method) is called when data is available or when an error is encountered on the file descriptor.

To use it, one must add the file descriptors to watch in the task's configureHook()

FileDescriptorActivity* fd_activity = dynamic_cast<FileDescriptorActivity*>(getActivity().get()); if (fd_activity) { fd_activity->watch(device_fd); // optional, set a timeout in milliseconds fd_activity->setTimeout(1000); // or in microseconds fd_activity->setTimeout_us(1000); }

Then, updateHook() and – when in ERROR state – errorHook() will be called when one of these three events happen:

The different cases can be tested in updateHook() as follows:

FileDescriptorActivity* fd_activity = dynamic_cast<FileDescriptorActivity*>(getActivity().get()); if (fd_activity) { if (fd_activity->hasError()) { } else if (fd_activity->hasTimeout()) { } else { // If there is more than one FD, discriminate. Otherwise, // we don't need to use isUpdated if (fd_activity->isUpdated(device_fd)) { } else if (fd_activity->isUpdated(another_fd)) { } } }

Definition at line 104 of file FileDescriptorActivity.hpp.

Constructor & Destructor Documentation

FileDescriptorActivity::FileDescriptorActivity ( int  priority,
base::RunnableInterface _r = 0,
const std::string &  name = "FileDescriptorActivity" 
)

Create a FileDescriptorActivity with a given priority and base::RunnableInterface instance. The default scheduler for NonPeriodicActivity objects is ORO_SCHED_RT.

Parameters
priorityThe priority of the underlying thread.
_rThe optional runner, if none, this->loop() is called.
nameThe name of the underlying thread.

Create a FileDescriptorActivity with a given priority and RunnableInterface instance. The default scheduler for NonPeriodicActivity objects is ORO_SCHED_RT.

Parameters
priorityThe priority of the underlying thread.
_rThe optional runner, if none, this->loop() is called.

Definition at line 78 of file FileDescriptorActivity.cpp.

FileDescriptorActivity::FileDescriptorActivity ( int  scheduler,
int  priority,
base::RunnableInterface _r = 0,
const std::string &  name = "FileDescriptorActivity" 
)

Create a FileDescriptorActivity with a given scheduler type, priority and base::RunnableInterface instance.

Parameters
schedulerThe scheduler in which the activitie's thread must run. Use ORO_SCHED_OTHER or ORO_SCHED_RT.
priorityThe priority of the underlying thread.
_rThe optional runner, if none, this->loop() is called.
nameThe name of the underlying thread.

Create a FileDescriptorActivity with a given scheduler type, priority and RunnableInterface instance.

Parameters
schedulerThe scheduler in which the activitie's thread must run. Use ORO_SCHED_OTHER or ORO_SCHED_RT.
priorityThe priority of the underlying thread.
_rThe optional runner, if none, this->loop() is called.

Definition at line 103 of file FileDescriptorActivity.cpp.

FileDescriptorActivity::FileDescriptorActivity ( int  scheduler,
int  priority,
Seconds  period,
base::RunnableInterface _r = 0,
const std::string &  name = "FileDescriptorActivity" 
)

Create a FileDescriptorActivity with a given scheduler type, priority, intended period, and RunnableInterface instance.

Parameters
schedulerThe scheduler in which the activitie's thread must run. Use ORO_SCHED_OTHER or ORO_SCHED_RT.
priorityThe priority of the underlying thread.
periodThe intended periodicity of the activity
_rThe optional runner, if none, this->loop() is called.
nameThe name of the underlying thread.

Definition at line 119 of file FileDescriptorActivity.cpp.

FileDescriptorActivity::FileDescriptorActivity ( int  scheduler,
int  priority,
Seconds  period,
unsigned  cpu_affinity,
base::RunnableInterface _r = 0,
const std::string &  name = "FileDescriptorActivity" 
)

Create a FileDescriptorActivity with a given scheduler type, priority, intended period, CPU affinity, and RunnableInterface instance.

Parameters
schedulerThe scheduler in which the activitie's thread must run. Use ORO_SCHED_OTHER or ORO_SCHED_RT.
priorityThe priority of the underlying thread.
periodThe intended periodicity of the activity
cpu_affinityThe prefered cpu to run on (a mask)
_rThe optional runner, if none, this->loop() is called.
nameThe name of the underlying thread.

Definition at line 135 of file FileDescriptorActivity.cpp.

FileDescriptorActivity::~FileDescriptorActivity ( )
virtual

Definition at line 151 of file FileDescriptorActivity.cpp.

Member Function Documentation

bool FileDescriptorActivity::breakLoop ( )
virtual
See also
base::RunnableInterface::breakLoop()

Reimplemented from RTT::Activity.

Definition at line 414 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::clearAllWatches ( )
virtual

Remove all FDs that are currently being watched

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 206 of file FileDescriptorActivity.cpp.

Seconds FileDescriptorActivity::getPeriod ( ) const
virtual

Get the intended period (not the actual running period)

Reimplemented from RTT::Activity.

Definition at line 156 of file FileDescriptorActivity.cpp.

int FileDescriptorActivity::getTimeout ( ) const
virtual

Get the timeout, in milliseconds, for waiting on the IO. Set to 0 for blocking behaviour (no timeout).

Returns
The timeout (milliseconds)

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 169 of file FileDescriptorActivity.cpp.

int FileDescriptorActivity::getTimeout_us ( ) const
virtual

Get the timeout, in microseconds, for waiting on the IO. Set to 0 for blocking behaviour (no timeout).

Returns
The timeout (microseconds)

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 171 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::hasError ( ) const
virtual

True if one of the file descriptors has a problem (for instance it has been closed)

This should only be used from within the base::RunnableInterface this activity is driving, i.e. in TaskContext::updateHook() or TaskContext::errorHook().

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 222 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::hasTimeout ( ) const
virtual

True if the base::RunnableInterface has been triggered because of a timeout, instead of because of new data is available.

This should only be used from within the base::RunnableInterface this activity is driving, i.e. in TaskContext::updateHook() or TaskContext::errorHook().

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 224 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::isRunning ( ) const
virtual

Query if the activity is initialized and executing. This is more strict than isActive(), it is only true after initialize() is executed and before finalize() is executed. More-over, an Activity may decide to be temporarily not running (not executing code), waiting for a signal to proceed. If this->isActive() and !this->isRunning() then the Activity is in a waiting state.

Returns
true if it is running, false otherwise

Reimplemented from RTT::Activity.

Definition at line 167 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::isUpdated ( int  fd) const
virtual

True if this specific FD has new data.

This should only be used from within the base::RunnableInterface this activity is driving, i.e. in TaskContext::updateHook() or TaskContext::errorHook().

Parameters
fdthe file descriptor

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 220 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::isWatched ( int  fd) const
virtual

True if this specific FD is being watched by the activity

Parameters
fdthe file descriptor

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 226 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::loop ( )
virtual
See also
base::RunnableInterface::loop()

Reimplemented from RTT::Activity.

Definition at line 303 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::setPeriod ( Seconds  period)
virtual

Set the intended period (not the actual running period)

Reimplemented from RTT::Activity.

Definition at line 159 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::setTimeout ( int  timeout)
virtual

Sets the timeout, in milliseconds, for waiting on the IO. Set to 0 for blocking behaviour (no timeout).

Precondition
0 <= timeout (otherwise an error is logged and timeout is ignored)
Parameters
timeoutThe timeout (milliseconds)

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 173 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::setTimeout_us ( int  timeout_us)
virtual

Sets the timeout, in microseconds, for waiting on the IO. Set to 0 for blocking behaviour (no timeout).

Precondition
0 <= timeout (otherwise an error is logged and timeout_us is ignored)
Parameters
timeoutThe timeout (microseconds)

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 177 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::start ( )
virtual

Start the activity. This will call RunnableInterface::initialize() and upon success, effectively start the activity, by running the RunnableInterface::step() or RunnableInterface::loop() in a thread.

See also
isPeriodic()
Returns
true if the activity is started, false otherwise

Reimplemented from RTT::Activity.

Definition at line 230 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::step ( )
virtual

Called by loop() when data is available on the file descriptor. By default, it calls step() on the associated runner interface (if any)

Reimplemented from RTT::Activity.

Definition at line 424 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::stop ( )
virtual

Stop the activity This will stop the activity by removing it from the 'run-queue' of a thread or call RunnableInterface::breakLoop(). If no errors occured, RunnableInterface::finalize() is called.

See also
isPeriodic()
Returns
true if the activity is stopped, false otherwise

Reimplemented from RTT::Activity.

Definition at line 440 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::timeout ( )
virtual

Always returns false.

Reimplemented from RTT::Activity.

Definition at line 286 of file FileDescriptorActivity.cpp.

bool FileDescriptorActivity::trigger ( )
virtual

Force calling step() even if no data is available on the file descriptor, and returns true if the signalling was successful

Reimplemented from RTT::Activity.

Definition at line 273 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::triggerUpdateSets ( )
private

Internal method that makes sure loop() takes into account modifications in the set of watched FDs

Definition at line 212 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::unwatch ( int  fd)
virtual

Removes a file descriptor from the set of watched FDs

This method is thread-safe, i.e. it can be called from any thread

Parameters
fdthe file descriptor

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 200 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::watch ( int  fd)
virtual

Sets the file descriptor the activity should be listening to.

This method is thread-safe, i.e. it can be called from any thread

Parameters
fdthe file descriptor

Implements RTT::extras::FileDescriptorActivityInterface.

Definition at line 188 of file FileDescriptorActivity.cpp.

void FileDescriptorActivity::work ( base::RunnableInterface::WorkReason  reason)
virtual

Called by loop() when data is available on the file descriptor. By default, it calls step() on the associated runner interface (if any)

Reimplemented from RTT::Activity.

Definition at line 432 of file FileDescriptorActivity.cpp.

Member Data Documentation

const char FileDescriptorActivity::CMD_ANY_COMMAND = 0
staticprivate

Definition at line 119 of file FileDescriptorActivity.hpp.

bool RTT::extras::FileDescriptorActivity::m_break_loop
private

Definition at line 121 of file FileDescriptorActivity.hpp.

RTT::os::Mutex RTT::extras::FileDescriptorActivity::m_command_mutex
private

Definition at line 120 of file FileDescriptorActivity.hpp.

fd_set RTT::extras::FileDescriptorActivity::m_fd_set
private

Definition at line 114 of file FileDescriptorActivity.hpp.

fd_set RTT::extras::FileDescriptorActivity::m_fd_work
private

Definition at line 115 of file FileDescriptorActivity.hpp.

bool RTT::extras::FileDescriptorActivity::m_has_error
private

Definition at line 116 of file FileDescriptorActivity.hpp.

bool RTT::extras::FileDescriptorActivity::m_has_timeout
private

Definition at line 117 of file FileDescriptorActivity.hpp.

int RTT::extras::FileDescriptorActivity::m_interrupt_pipe[2]
private

Definition at line 109 of file FileDescriptorActivity.hpp.

RTT::os::Mutex RTT::extras::FileDescriptorActivity::m_lock
mutableprivate

intended period

Lock that protects the access to m_fd_set and m_watched_fds

Definition at line 113 of file FileDescriptorActivity.hpp.

Seconds RTT::extras::FileDescriptorActivity::m_period
private

timeout in microseconds

Definition at line 111 of file FileDescriptorActivity.hpp.

bool RTT::extras::FileDescriptorActivity::m_running
private

Definition at line 108 of file FileDescriptorActivity.hpp.

int RTT::extras::FileDescriptorActivity::m_timeout_us
private

Definition at line 110 of file FileDescriptorActivity.hpp.

bool RTT::extras::FileDescriptorActivity::m_trigger
private

Definition at line 122 of file FileDescriptorActivity.hpp.

bool RTT::extras::FileDescriptorActivity::m_update_sets
private

Definition at line 123 of file FileDescriptorActivity.hpp.

std::set<int> RTT::extras::FileDescriptorActivity::m_watched_fds
private

Definition at line 107 of file FileDescriptorActivity.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