Fawkes API
Fawkes Development Version
|
Joystick acqusition thread for Linux joystick API. More...
#include "acquisition_thread.h"
Public Member Functions | |
JoystickAcquisitionThread () | |
Constructor. More... | |
JoystickAcquisitionThread (const char *device_file, JoystickBlackBoardHandler *handler, fawkes::Logger *logger) | |
Alternative constructor. More... | |
virtual void | init () |
Initialize the thread. More... | |
virtual void | finalize () |
Finalize the thread. More... | |
virtual void | loop () |
Code to execute in the thread. More... | |
bool | lock_if_new_data () |
Lock data if fresh. More... | |
void | unlock () |
Unlock data. More... | |
char | num_axes () const |
Get number of axes. More... | |
char | num_buttons () const |
Get number of buttons. More... | |
const char * | joystick_name () const |
Get joystick name. More... | |
unsigned int | pressed_buttons () const |
Pressed buttons. More... | |
float * | axis_values () |
Get values for the axes. More... | |
JoystickForceFeedback * | ff () const |
Access force feedback of joystick. More... | |
![]() | |
virtual | ~Thread () |
Virtual destructor. More... | |
bool | prepare_finalize () |
Prepare finalization. More... | |
virtual bool | prepare_finalize_user () |
Prepare finalization user implementation. More... | |
void | cancel_finalize () |
Cancel finalization. More... | |
void | start (bool wait=true) |
Call this method to start the thread. More... | |
void | cancel () |
Cancel a thread. More... | |
void | join () |
Join the thread. More... | |
void | detach () |
Detach the thread. More... | |
void | kill (int sig) |
Send signal to a thread. More... | |
bool | operator== (const Thread &thread) |
Check if two threads are the same. More... | |
void | wakeup () |
Wake up thread. More... | |
void | wakeup (Barrier *barrier) |
Wake up thread and wait for barrier afterwards. More... | |
void | wait_loop_done () |
Wait for the current loop iteration to finish. More... | |
OpMode | opmode () const |
Get operation mode. More... | |
pthread_t | thread_id () const |
Get ID of thread. More... | |
bool | started () const |
Check if thread has been started. More... | |
bool | cancelled () const |
Check if thread has been cancelled. More... | |
bool | detached () const |
Check if thread has been detached. More... | |
bool | running () const |
Check if the thread is running. More... | |
bool | waiting () const |
Check if thread is currently waiting for wakeup. More... | |
const char * | name () const |
Get name of thread. More... | |
void | set_flags (uint32_t flags) |
Set all flags in one go. More... | |
void | set_flag (uint32_t flag) |
Set flag for the thread. More... | |
void | unset_flag (uint32_t flag) |
Unset flag. More... | |
bool | flagged_bad () const |
Check if FLAG_BAD was set. More... | |
void | set_delete_on_exit (bool del) |
Set whether the thread should be deleted on exit. More... | |
void | set_prepfin_hold (bool hold) |
Hold prepare_finalize(). More... | |
void | add_notification_listener (ThreadNotificationListener *notification_listener) |
Add notification listener. More... | |
void | remove_notification_listener (ThreadNotificationListener *notification_listener) |
Remove notification listener. More... | |
void | notify_of_failed_init () |
Notify of failed init. More... | |
![]() | |
LoggingAspect () | |
Constructor. More... | |
virtual | ~LoggingAspect () |
Virtual empty Destructor. More... | |
void | init_LoggingAspect (Logger *logger) |
Set the logger. More... | |
![]() | |
const std::list< const char * > & | get_aspects () const |
Get list of aspect names attached to a aspected thread. More... | |
![]() | |
ConfigurableAspect () | |
Constructor. More... | |
virtual | ~ConfigurableAspect () |
Virtual empty Destructor. More... | |
void | init_ConfigurableAspect (Configuration *config) |
Set the configuration It is guaranteed that this is called for a configurable thread before Thread::start() is called (when running regularly inside Fawkes). More... | |
Protected Member Functions | |
virtual void | run () |
Stub to see name in backtrace for easier debugging. More... | |
![]() | |
Thread (const char *name) | |
Constructor. More... | |
Thread (const char *name, OpMode op_mode) | |
Constructor. More... | |
void | exit () |
Exit the thread. More... | |
void | test_cancel () |
Set cancellation point. More... | |
void | yield () |
Yield the processor to another thread or process. More... | |
void | set_opmode (OpMode op_mode) |
Set operation mode. More... | |
void | set_prepfin_conc_loop (bool concurrent=true) |
Set concurrent execution of prepare_finalize() and loop(). More... | |
void | set_coalesce_wakeups (bool coalesce=true) |
Set wakeup coalescing. More... | |
void | set_name (const char *format,...) |
Set name of thread. More... | |
virtual void | once () |
Execute an action exactly once. More... | |
bool | wakeup_pending () |
Check if wakeups are pending. More... | |
![]() | |
void | add_aspect (const char *name) |
Add an aspect to a thread. More... | |
Additional Inherited Members | |
![]() | |
enum | OpMode { OPMODE_CONTINUOUS, OPMODE_WAITFORWAKEUP } |
Thread operation mode. More... | |
enum | CancelState { CANCEL_ENABLED, CANCEL_DISABLED } |
Cancel state. More... | |
![]() | |
static Thread * | current_thread () |
Get the Thread instance of the currently running thread. More... | |
static Thread * | current_thread_noexc () throw () |
Similar to current_thread, but does never throw an exception. More... | |
static pthread_t | current_thread_id () |
Get the ID of the currently running thread. More... | |
static void | init_main () |
Initialize Thread wrapper instance for main thread. More... | |
static void | destroy_main () |
Destroy main thread wrapper instance. More... | |
static void | set_cancel_state (CancelState new_state, CancelState *old_state=0) |
Set the cancel state of the current thread. More... | |
![]() | |
static const unsigned int | FLAG_BAD = 0x00000001 |
Standard thread flag: "thread is bad". More... | |
![]() | |
bool | finalize_prepared |
True if prepare_finalize() has been called and was not stopped with a cancel_finalize(), false otherwise. More... | |
Mutex * | loop_mutex |
Mutex that is used to protect a call to loop(). More... | |
Mutex * | loopinterrupt_antistarve_mutex |
Mutex to avoid starvation when trying to lock loop_mutex. More... | |
![]() | |
Logger * | logger |
This is the Logger member used to access the logger. More... | |
![]() | |
Configuration * | config |
This is the Configuration member used to access the configuration. More... | |
Joystick acqusition thread for Linux joystick API.
Definition at line 43 of file acquisition_thread.h.
JoystickAcquisitionThread::JoystickAcquisitionThread | ( | ) |
Constructor.
Definition at line 57 of file acquisition_thread.cpp.
References fawkes::LoggingAspect::logger, and fawkes::Thread::set_prepfin_conc_loop().
JoystickAcquisitionThread::JoystickAcquisitionThread | ( | const char * | device_file, |
JoystickBlackBoardHandler * | handler, | ||
fawkes::Logger * | logger | ||
) |
Alternative constructor.
This constructor is meant to be used to create an instance that is used outside of Fawkes.
device_file | joystick device file |
handler | BlackBoard handler that will post data to the BlackBoard |
logger | logging instance |
Definition at line 76 of file acquisition_thread.cpp.
References init(), fawkes::LoggingAspect::logger, and fawkes::Thread::set_prepfin_conc_loop().
float * JoystickAcquisitionThread::axis_values | ( | ) |
Get values for the axes.
Definition at line 436 of file acquisition_thread.cpp.
Referenced by JoystickSensorThread::loop().
|
inline |
Access force feedback of joystick.
Definition at line 69 of file acquisition_thread.h.
Referenced by JoystickActThread::MessageProcessor::process(), and JoystickActThread::MessageProcessor::process_message().
|
virtual |
Finalize the thread.
This method is executed just before the thread is canceled and destroyed. It is always preceeded by a call to prepare_finalize(). If this is not the case this is a failure. The condition can be checked with the boolean variable finalize_prepared.
This method is meant to be used in conjunction with aspects and to cover thread inter-dependencies. This routine MUST bring the thread into a safe state such that it may be canceled and destroyed afterwards. If there is any reason that this cannot happen make your prepare_finalize() reports so.
This method is called by the thread manager just before the thread is being cancelled. Here you can do whatever steps are necessary just before the thread is cancelled. Note that you thread is still running and might be in the middle of a loop, so it is not a good place to give up on all resources used. Mind segmentation faults that could happen. Protect the area with a mutex that you lock at the beginning of your loop and free in the end, and that you lock at the beginning of finalize and then never unlock. Also not that the finalization may be canceled afterwards. The next thing that happens is that either the thread is canceled and destroyed or that the finalization is canceled and the thread has to run again.
Finalize is called on a thread just before it is deleted. It is guaranteed to be called on a fully initialized thread (if no exception is thrown in init()) (this guarantee holds in the Fawkes framework).
The default implementation does nothing besides throwing an exception if prepare_finalize() has not been called.
Exception | thrown if prepare_finalize() has not been called. |
Reimplemented from fawkes::Thread.
Definition at line 210 of file acquisition_thread.cpp.
|
virtual |
Initialize the thread.
This method is meant to be used in conjunction with aspects. Some parts of the initialization may only happen after some aspect of the thread has been initialized. Implement the init method with these actions. It is guaranteed to be called just after all aspects have been initialized and only once in the lifetime of the thread. Throw an exception if any problem occurs and the thread should not run.
Just because your init() routine suceeds and everything looks fine for this thread does not automatically imply that it will run. If it belongs to a group of threads in a ThreadList and any of the other threads fail to initialize then no thread from this group is run and thus this thread will never run. In that situation finalize() is called for this very instance, prepare_finalize() however is not called.
Reimplemented from fawkes::Thread.
Definition at line 92 of file acquisition_thread.cpp.
References fawkes::Exception::append(), JoystickForceFeedback::can_constant(), JoystickForceFeedback::can_custom(), JoystickForceFeedback::can_damper(), JoystickForceFeedback::can_friction(), JoystickForceFeedback::can_inertia(), JoystickForceFeedback::can_periodic(), JoystickForceFeedback::can_ramp(), JoystickForceFeedback::can_rumble(), JoystickForceFeedback::can_saw_down(), JoystickForceFeedback::can_saw_up(), JoystickForceFeedback::can_sine(), JoystickForceFeedback::can_spring(), JoystickForceFeedback::can_square(), JoystickForceFeedback::can_triangle(), fawkes::ConfigurableAspect::config, fawkes::Configuration::get_bool(), fawkes::Configuration::get_float(), fawkes::Configuration::get_string(), fawkes::Configuration::get_uint(), JoystickBlackBoardHandler::joystick_plugged(), fawkes::Logger::log_debug(), fawkes::Logger::log_info(), fawkes::Logger::log_warn(), fawkes::LoggingAspect::logger, and fawkes::Thread::name().
Referenced by JoystickAcquisitionThread().
const char * JoystickAcquisitionThread::joystick_name | ( | ) | const |
bool JoystickAcquisitionThread::lock_if_new_data | ( | ) |
Lock data if fresh.
If new data has been received since get_distance_data() or get_echo_data() was called last the data is locked, no new data can arrive until you call unlock(), otherwise the lock is immediately released after checking.
Definition at line 364 of file acquisition_thread.cpp.
References fawkes::Mutex::lock(), and fawkes::Mutex::unlock().
Referenced by JoystickSensorThread::loop().
|
virtual |
Code to execute in the thread.
Implement this method to hold the code you want to be executed continously. If you do not implement this method, the default is that the thread will exit. This is useful if you choose to only implement once().
Reimplemented from fawkes::Thread.
Definition at line 219 of file acquisition_thread.cpp.
References JoystickBlackBoardHandler::joystick_changed(), JoystickBlackBoardHandler::joystick_unplugged(), fawkes::Mutex::lock(), fawkes::Logger::log_warn(), fawkes::LoggingAspect::logger, fawkes::Thread::name(), and fawkes::Mutex::unlock().
char JoystickAcquisitionThread::num_axes | ( | ) | const |
Get number of axes.
Definition at line 390 of file acquisition_thread.cpp.
Referenced by JoystickSensorThread::loop().
char JoystickAcquisitionThread::num_buttons | ( | ) | const |
Get number of buttons.
Definition at line 400 of file acquisition_thread.cpp.
Referenced by JoystickSensorThread::loop().
unsigned int JoystickAcquisitionThread::pressed_buttons | ( | ) | const |
Pressed buttons.
Definition at line 420 of file acquisition_thread.cpp.
Referenced by JoystickSensorThread::loop().
|
inlineprotectedvirtual |
Stub to see name in backtrace for easier debugging.
Reimplemented from fawkes::Thread.
Definition at line 72 of file acquisition_thread.h.
References fawkes::Thread::run().
void JoystickAcquisitionThread::unlock | ( | ) |
Unlock data.
Definition at line 379 of file acquisition_thread.cpp.
References fawkes::Mutex::unlock().
Referenced by JoystickSensorThread::loop().