Fawkes API
Fawkes Development Version
|
FireVision base thread. More...
#include "base_thread.h"
Public Member Functions | |
FvBaseThread () | |
Constructor. More... | |
virtual | ~FvBaseThread () |
Destructor. More... | |
virtual void | init () |
Initialize the thread. More... | |
virtual void | loop () |
Thread loop. More... | |
virtual void | finalize () |
Finalize the thread. More... | |
virtual firevision::VisionMaster * | vision_master () |
Get vision master. More... | |
virtual firevision::Camera * | register_for_camera (const char *camera_string, fawkes::Thread *thread, firevision::colorspace_t cspace=firevision::YUV422_PLANAR) |
Register thread for camera. More... | |
virtual firevision::Camera * | register_for_raw_camera (const char *camera_string, fawkes::Thread *thread) |
Register thread for camera. More... | |
virtual void | unregister_thread (fawkes::Thread *thread) |
Unregister a thread. More... | |
virtual firevision::CameraControl * | acquire_camctrl (const char *cam_string) |
Retrieve a CameraControl for the specified camera string. More... | |
virtual void | release_camctrl (firevision::CameraControl *cc) |
Release a camera control. More... | |
virtual bool | thread_started (fawkes::Thread *thread) throw () |
Thread started successfully. More... | |
virtual bool | thread_init_failed (fawkes::Thread *thread) throw () |
Thread initialization failed. 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... | |
![]() | |
BlockedTimingAspect (WakeupHook wakeup_hook) | |
Constructor. More... | |
virtual | ~BlockedTimingAspect () |
Virtual empty destructor. More... | |
WakeupHook | blockedTimingAspectHook () const |
Get the wakeup hook. More... | |
![]() | |
const std::list< const char * > & | get_aspects () const |
Get list of aspect names attached to a aspected thread. More... | |
![]() | |
LoggingAspect () | |
Constructor. More... | |
virtual | ~LoggingAspect () |
Virtual empty Destructor. More... | |
void | init_LoggingAspect (Logger *logger) |
Set the logger. More... | |
![]() | |
VisionMasterAspect (firevision::VisionMaster *master) __attribute__((nonnull)) | |
Constructor. More... | |
virtual | ~VisionMasterAspect () |
Virtual empty Destructor. More... | |
firevision::VisionMaster * | vision_master () |
Get vision master. More... | |
![]() | |
ClockAspect () | |
Constructor. More... | |
virtual | ~ClockAspect () |
Virtual empty destructor. More... | |
void | init_ClockAspect (Clock *clock) |
Set the clock. More... | |
![]() | |
ThreadProducerAspect () | |
Constructor. More... | |
virtual | ~ThreadProducerAspect () |
Virtual empty destructor. More... | |
void | init_ThreadProducerAspect (ThreadCollector *collector) |
Init thread producer aspect. 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... | |
![]() | |
virtual | ~ThreadNotificationListener () |
Virtual empty destructor. More... | |
![]() | |
virtual | ~VisionMaster () |
Virtual empty destructor. More... | |
template<class CC > | |
CC * | acquire_camctrl (const char *camera_string) |
Retrieve a typed camera control instance. More... | |
template<class CC > | |
CC * | acquire_camctrl (const char *camera_string, CC *&cc) |
Retrieve a typed camera control instance. More... | |
template<class CC > | |
CC * | register_for_raw_camera (const char *camera_string, fawkes::Thread *thread) |
Get typed raw camera. More... | |
Protected Member Functions | |
virtual void | run () |
Stub to see name in backtrace for easier debugging. More... | |
virtual firevision::CameraControl * | acquire_camctrl (const char *cam_string, const std::type_info &typeinf) |
Retrieve a CameraControl for the specified camera string and type info. 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... | |
![]() | |
enum | WakeupHook { WAKEUP_HOOK_PRE_LOOP, WAKEUP_HOOK_SENSOR_ACQUIRE, WAKEUP_HOOK_SENSOR_PREPARE, WAKEUP_HOOK_SENSOR_PROCESS, WAKEUP_HOOK_WORLDSTATE, WAKEUP_HOOK_THINK, WAKEUP_HOOK_SKILL, WAKEUP_HOOK_ACT, WAKEUP_HOOK_ACT_EXEC, WAKEUP_HOOK_POST_LOOP } |
Type to define at which hook the thread is woken up. 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 char * | blocked_timing_hook_to_string (WakeupHook hook) |
Get string for wakeup hook. 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... | |
![]() | |
Clock * | clock |
By means of this member access to the clock is given. More... | |
![]() | |
ThreadCollector * | thread_collector |
Thread collector. More... | |
![]() | |
Configuration * | config |
This is the Configuration member used to access the configuration. More... | |
FireVision base thread.
This implements the functionality of the FvBasePlugin.
Definition at line 46 of file base_thread.h.
FvBaseThread::FvBaseThread | ( | ) |
Constructor.
Definition at line 56 of file base_thread.cpp.
|
virtual |
Destructor.
Definition at line 68 of file base_thread.cpp.
|
virtual |
Retrieve a CameraControl for the specified camera string.
This control (if available) can be used to control certain aspects of the Camera. The cam_string
argument either is the string that has been used to register for a particular camera, or it is a string denoting a camera control by itself. In the former case the vision master will look if the camera has been registered, and then checks if the camera provides a camera control. If so the control is returned. Note that it might implement multiple different camera controls. If you want a specific camera control use one of the template methods to get a correctly typed and verified control. If no camera that matches the cam_string
is found, the vision master will try to instantiate a new camera control using the cam_string
as argument to the CameraControlFactory.
cam_string | Camera argument string, see method description for details |
Exception | no camera was found matching the cam_string and the factory could not instantiate a camera control with the given string. |
Implements firevision::VisionMaster.
Definition at line 339 of file base_thread.cpp.
References firevision::CameraArgumentParser::cam_id(), firevision::CameraArgumentParser::cam_type(), and fawkes::LockMap< KeyType, ValueType, LessKey >::mutex().
|
protectedvirtual |
Retrieve a CameraControl for the specified camera string and type info.
This utility method is used by the template methods to instantiate the cameras with a specified intended type.
cam_string | Camera argument string, see method description for details |
typeinf | type info for intended camera control type |
Exception | no camera was found matching the cam_string and the factory could not instantiate a camera control with the given string. |
Implements firevision::VisionMaster.
Definition at line 355 of file base_thread.cpp.
References firevision::CameraArgumentParser::cam_id(), firevision::CameraArgumentParser::cam_type(), and fawkes::LockMap< KeyType, ValueType, LessKey >::mutex().
|
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 85 of file base_thread.cpp.
References fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), fawkes::LockList< Type >::lock(), fawkes::ThreadCollector::remove(), fawkes::ThreadProducerAspect::thread_collector, fawkes::LockMap< KeyType, ValueType, LessKey >::unlock(), and fawkes::LockList< Type >::unlock().
|
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 75 of file base_thread.cpp.
|
virtual |
Thread loop.
Reimplemented from fawkes::Thread.
Definition at line 106 of file base_thread.cpp.
References FvAcquisitionThread::AqtContinuous, FvAcquisitionThread::AqtCyclic, fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), fawkes::Logger::log_info(), fawkes::Logger::log_warn(), fawkes::LoggingAspect::logger, fawkes::Thread::name(), fawkes::ThreadCollector::remove(), fawkes::ThreadProducerAspect::thread_collector, fawkes::LockMap< KeyType, ValueType, LessKey >::unlock(), and fawkes::Barrier::wait().
|
virtual |
Register thread for camera.
This will register a relation between the given thread and the camera identified by the camera string. If the requested camera has not been opened before this is done and the camera is started. If that fails for whatever reason an exception is thrown. In that case the thread is not registered with the vision master. If the camera is available the thread is registered with the vision master. From then on it is woken up whenever new image data is available and it will wait for the thread to finished computation on that very image. It is a critical error that can not be recovered if the thread fails for whatever reason. If there is a critical error condition in the vision thread it must not stop execution but just the computation.
camera_string | camera that can be used by CameraFactory to open a camera. |
thread | thread to register for this camera |
cspace | the colorspace in which the images should be provided for the camera. Note that using images in different formats at the same time can cause a severe performance penalty. The default is to produce YUV422_PLANAR images, which is used in the FireVision framework as main image format. |
Implements firevision::VisionMaster.
Definition at line 230 of file base_thread.cpp.
References fawkes::ThreadCollector::add(), fawkes::Thread::add_notification_listener(), FvAqtVisionThreads::add_waiting_thread(), fawkes::Exception::append(), firevision::CameraArgumentParser::cam_id(), firevision::CameraArgumentParser::cam_type(), FvAcquisitionThread::camera_instance(), fawkes::ClockAspect::clock, fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), fawkes::Logger::log_info(), fawkes::LoggingAspect::logger, fawkes::Thread::name(), firevision::Camera::open(), fawkes::ThreadProducerAspect::thread_collector, fawkes::LockMap< KeyType, ValueType, LessKey >::unlock(), fawkes::VisionAspect::vision_thread_mode(), and FvAcquisitionThread::vision_threads.
Referenced by register_for_raw_camera().
|
virtual |
Register thread for camera.
This will register a relation between the given thread and the camera identified by the camera string similar to register_for_camera(). However, unlike register_for_camera() this method will provide access to the raw camera implementation, without possibly proxies. Once you gathered the camera, you can dynamically cast it to the expected camera type (or use the template method instead. Raw access to a camera is only granted for a single thread. Note that you may not call capture() or dispose() on the camera, this will still be done by the vision master, as the camera may be used by other threads that registered for the camera with register_for_camera().
camera_string | camera that can be used by CameraFactory to open a camera. |
thread | thread to register for this camera |
Implements firevision::VisionMaster.
Definition at line 304 of file base_thread.cpp.
References firevision::CameraArgumentParser::cam_id(), firevision::CameraArgumentParser::cam_type(), fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), fawkes::LockList< Type >::lock(), register_for_camera(), fawkes::LockMap< KeyType, ValueType, LessKey >::unlock(), and fawkes::LockList< Type >::unlock().
|
virtual |
Release a camera control.
This has to be called when you are done with the camera control. This will release the control and it is no longer valid. The vision master might collect the memory that has been used for the control.
cc | camera control instance to release |
Implements firevision::VisionMaster.
Definition at line 372 of file base_thread.cpp.
References fawkes::Barrier::count(), fawkes::LockList< Type >::lock(), and fawkes::LockList< Type >::unlock().
|
inlineprotectedvirtual |
Stub to see name in backtrace for easier debugging.
Reimplemented from fawkes::Thread.
Definition at line 82 of file base_thread.h.
References fawkes::Thread::run().
|
virtual |
Thread initialization failed.
This method is called by ThreadList if one of the threads in the list failed to initialize. This is not necessarily the thread that you registered the notification for. However, the argument is always the thread that you registered for, no matter which thread in the list failed.
thread | thread that you registered for |
Implements fawkes::ThreadNotificationListener.
Definition at line 460 of file base_thread.cpp.
References fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), and fawkes::LockMap< KeyType, ValueType, LessKey >::unlock().
|
virtual |
Thread started successfully.
This is called by the thread itself when the thread started successfully.
thread | thread that started successfully |
Implements fawkes::ThreadNotificationListener.
Definition at line 443 of file base_thread.cpp.
References fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), and fawkes::LockMap< KeyType, ValueType, LessKey >::unlock().
|
virtual |
Unregister a thread.
The thread is unregistered and it is removed from the internal structures. The thread is no longer called for new image material that can be processed.
If the unregistered thread was the last thread accessing the camera, it shall be held open for a specified time, such that if the thread is just being restarted the camera does not have to be re-opened. The time to wait is defined by the implementation.
thread | thread to unregister |
Implements firevision::VisionMaster.
Definition at line 399 of file base_thread.cpp.
References FvAcquisitionThread::AqtContinuous, fawkes::LockMap< KeyType, ValueType, LessKey >::lock(), fawkes::Logger::log_info(), fawkes::LoggingAspect::logger, fawkes::Thread::name(), and fawkes::LockMap< KeyType, ValueType, LessKey >::unlock().
|
virtual |