Fawkes API  Fawkes Development Version
Bumblebee2Thread Class Reference

Thread to acquire data from Bumblebee2 stereo camera. More...

#include "bumblebee2_thread.h"

Inheritance diagram for Bumblebee2Thread:

Public Member Functions

 Bumblebee2Thread ()
 Constructor. More...
 
virtual ~Bumblebee2Thread ()
 Destructor. More...
 
virtual void init ()
 Initialize the thread. More...
 
virtual void loop ()
 Code to execute in the thread. More...
 
virtual void finalize ()
 Finalize the thread. More...
 
- Public Member Functions inherited from fawkes::Thread
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...
 
- Public Member Functions inherited from fawkes::BlockedTimingAspect
 BlockedTimingAspect (WakeupHook wakeup_hook)
 Constructor. More...
 
virtual ~BlockedTimingAspect ()
 Virtual empty destructor. More...
 
WakeupHook blockedTimingAspectHook () const
 Get the wakeup hook. More...
 
- Public Member Functions inherited from fawkes::Aspect
const std::list< const char * > & get_aspects () const
 Get list of aspect names attached to a aspected thread. More...
 
- Public Member Functions inherited from fawkes::ClockAspect
 ClockAspect ()
 Constructor. More...
 
virtual ~ClockAspect ()
 Virtual empty destructor. More...
 
void init_ClockAspect (Clock *clock)
 Set the clock. More...
 
- Public Member Functions inherited from fawkes::LoggingAspect
 LoggingAspect ()
 Constructor. More...
 
virtual ~LoggingAspect ()
 Virtual empty Destructor. More...
 
void init_LoggingAspect (Logger *logger)
 Set the logger. More...
 
- Public Member Functions inherited from fawkes::ConfigurableAspect
 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...
 
- Public Member Functions inherited from fawkes::BlackBoardAspect
 BlackBoardAspect (const char *owner=NULL)
 Constructor. More...
 
virtual ~BlackBoardAspect ()
 Virtual empty destructor. More...
 
void init_BlackBoardAspect (BlackBoard *bb)
 Init BlackBoard aspect. More...
 
- Public Member Functions inherited from fawkes::TransformAspect
 TransformAspect (Mode mode=ONLY_LISTENER, const char *frame_id=0)
 Constructor. More...
 
virtual ~TransformAspect ()
 Virtual empty destructor. More...
 
void init_TransformAspect (BlackBoard *blackboard, tf::Transformer *transformer, const char *thread_name)
 Init transform aspect. More...
 
void finalize_TransformAspect ()
 Finalize transform aspect. More...
 
- Public Member Functions inherited from fawkes::PointCloudAspect
 PointCloudAspect ()
 Constructor. More...
 
virtual ~PointCloudAspect ()
 Virtual empty Destructor. More...
 
void init_PointCloudAspect (PointCloudManager *pcl_manager)
 Set URL manager. More...
 

Protected Member Functions

virtual void run ()
 Stub to see name in backtrace for easier debugging. More...
 
- Protected Member Functions inherited from fawkes::Thread
 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...
 
- Protected Member Functions inherited from fawkes::Aspect
void add_aspect (const char *name)
 Add an aspect to a thread. More...
 
- Protected Member Functions inherited from fawkes::TransformAspect
void tf_enable_publisher (const char *frame_id=0)
 Late enabling of publisher. More...
 
void tf_add_publisher (const char *frame_id_format,...)
 Late add of publisher. More...
 

Additional Inherited Members

- Public Types inherited from fawkes::Thread
enum  OpMode { OPMODE_CONTINUOUS, OPMODE_WAITFORWAKEUP }
 Thread operation mode. More...
 
enum  CancelState { CANCEL_ENABLED, CANCEL_DISABLED }
 Cancel state. More...
 
- Public Types inherited from fawkes::BlockedTimingAspect
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...
 
- Public Types inherited from fawkes::TransformAspect
enum  Mode {
  ONLY_LISTENER, ONLY_PUBLISHER, DEFER_PUBLISHER, BOTH,
  BOTH_DEFER_PUBLISHER
}
 Enumeration describing the desired mode of operation. More...
 
- Static Public Member Functions inherited from fawkes::Thread
static Threadcurrent_thread ()
 Get the Thread instance of the currently running thread. More...
 
static Threadcurrent_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 Public Member Functions inherited from fawkes::BlockedTimingAspect
static const char * blocked_timing_hook_to_string (WakeupHook hook)
 Get string for wakeup hook. More...
 
- Static Public Attributes inherited from fawkes::Thread
static const unsigned int FLAG_BAD = 0x00000001
 Standard thread flag: "thread is bad". More...
 
- Protected Attributes inherited from fawkes::Thread
bool finalize_prepared
 True if prepare_finalize() has been called and was not stopped with a cancel_finalize(), false otherwise. More...
 
Mutexloop_mutex
 Mutex that is used to protect a call to loop(). More...
 
Mutexloopinterrupt_antistarve_mutex
 Mutex to avoid starvation when trying to lock loop_mutex. More...
 
- Protected Attributes inherited from fawkes::ClockAspect
Clockclock
 By means of this member access to the clock is given. More...
 
- Protected Attributes inherited from fawkes::LoggingAspect
Loggerlogger
 This is the Logger member used to access the logger. More...
 
- Protected Attributes inherited from fawkes::ConfigurableAspect
Configurationconfig
 This is the Configuration member used to access the configuration. More...
 
- Protected Attributes inherited from fawkes::BlackBoardAspect
BlackBoardblackboard
 This is the BlackBoard instance you can use to interact with the BlackBoard. More...
 
- Protected Attributes inherited from fawkes::TransformAspect
tf::Transformertf_listener
 This is the transform listener which saves transforms published by other threads in the system. More...
 
tf::TransformPublishertf_publisher
 This is the transform publisher which can be used to publish transforms via the blackboard. More...
 
std::map< std::string, tf::TransformPublisher * > tf_publishers
 Map of transform publishers created through the aspect. More...
 
- Protected Attributes inherited from fawkes::PointCloudAspect
PointCloudManagerpcl_manager
 Manager to distribute and access point clouds. More...
 

Detailed Description

Thread to acquire data from Bumblebee2 stereo camera.

Author
Tim Niemueller

Definition at line 59 of file bumblebee2_thread.h.

Constructor & Destructor Documentation

◆ Bumblebee2Thread()

Bumblebee2Thread::Bumblebee2Thread ( )

Constructor.

Definition at line 76 of file bumblebee2_thread.cpp.

◆ ~Bumblebee2Thread()

Bumblebee2Thread::~Bumblebee2Thread ( )
virtual

Destructor.

Definition at line 85 of file bumblebee2_thread.cpp.

Member Function Documentation

◆ finalize()

void Bumblebee2Thread::finalize ( )
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.

Exceptions
Exceptionthrown if prepare_finalize() has not been called.
See also
prepare_finalize()
cancel_finalize()

Reimplemented from fawkes::Thread.

Definition at line 466 of file bumblebee2_thread.cpp.

References fawkes::BlackBoardAspect::blackboard, firevision::Bumblebee2Camera::close(), fawkes::BlackBoard::close(), fawkes::Logger::log_warn(), fawkes::LoggingAspect::logger, fawkes::Thread::name(), fawkes::PointCloudAspect::pcl_manager, fawkes::PointCloudManager::remove_pointcloud(), fawkes::RefPtr< T_CppObject >::reset(), and firevision::FirewireCamera::stop().

Referenced by init().

◆ init()

void Bumblebee2Thread::init ( )
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.

See also
Fawkes Thread Aspects

Reimplemented from fawkes::Thread.

Definition at line 91 of file bumblebee2_thread.cpp.

References fawkes::PointCloudManager::add_pointcloud(), fawkes::BlackBoardAspect::blackboard, fawkes::ClockAspect::clock, fawkes::ConfigurableAspect::config, finalize(), fawkes::Configuration::get_bool(), fawkes::Configuration::get_float(), fawkes::Configuration::get_int(), fawkes::Configuration::get_string(), fawkes::Configuration::get_uint(), fawkes::Logger::log_debug(), fawkes::LoggingAspect::logger, fawkes::Thread::name(), fawkes::BlackBoard::open_for_writing(), fawkes::PointCloudAspect::pcl_manager, fawkes::SwitchInterface::set_enabled(), fawkes::OpenCVStereoParamsInterface::set_min_disparity(), fawkes::OpenCVStereoParamsInterface::set_num_disparities(), fawkes::OpenCVStereoParamsInterface::set_pre_filter_cap(), fawkes::OpenCVStereoParamsInterface::set_pre_filter_size(), fawkes::OpenCVStereoParamsInterface::set_pre_filter_type(), fawkes::OpenCVStereoParamsInterface::set_sad_window_size(), fawkes::OpenCVStereoParamsInterface::set_speckle_range(), fawkes::OpenCVStereoParamsInterface::set_speckle_window_size(), fawkes::OpenCVStereoParamsInterface::set_texture_threshold(), fawkes::OpenCVStereoParamsInterface::set_try_smaller_windows(), fawkes::OpenCVStereoParamsInterface::set_uniqueness_ratio(), fawkes::Interface::write(), and firevision::Bumblebee2Camera::write_triclops_config_from_camera_to_file().

◆ loop()

void Bumblebee2Thread::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 517 of file bumblebee2_thread.cpp.

References firevision::SharedMemoryImageBuffer::buffer(), firevision::Bumblebee2Camera::capture(), fawkes::ClockAspect::clock, firevision::Bumblebee2Camera::decode_bayer(), firevision::Bumblebee2Camera::deinterlace_stereo(), firevision::FirewireCamera::dispose_buffer(), fawkes::SwitchInterface::is_enabled(), fawkes::SharedMemory::lock_for_write(), fawkes::Logger::log_warn(), fawkes::LoggingAspect::logger, fawkes::Interface::msgq_empty(), fawkes::Interface::msgq_first_safe(), fawkes::Interface::msgq_pop(), fawkes::Thread::name(), fawkes::SharedMemory::num_attached(), fawkes::tf::TransformPublisher::send_transform(), firevision::SharedMemoryImageBuffer::set_capture_time(), fawkes::SwitchInterface::set_enabled(), fawkes::OpenCVStereoParamsInterface::set_min_disparity(), fawkes::OpenCVStereoParamsInterface::set_num_disparities(), fawkes::OpenCVStereoParamsInterface::set_pre_filter_cap(), fawkes::OpenCVStereoParamsInterface::set_pre_filter_size(), fawkes::OpenCVStereoParamsInterface::set_pre_filter_type(), fawkes::OpenCVStereoParamsInterface::set_sad_window_size(), fawkes::OpenCVStereoParamsInterface::set_speckle_range(), fawkes::OpenCVStereoParamsInterface::set_speckle_window_size(), fawkes::OpenCVStereoParamsInterface::set_texture_threshold(), fawkes::OpenCVStereoParamsInterface::set_try_smaller_windows(), fawkes::OpenCVStereoParamsInterface::set_uniqueness_ratio(), fawkes::tf::StampedTransform::stamp, fawkes::Time::stamp(), fawkes::TransformAspect::tf_publisher, fawkes::SharedMemory::unlock(), fawkes::RefPtr< T_CppObject >::use_count(), and fawkes::Interface::write().

◆ run()

virtual void Bumblebee2Thread::run ( )
inlineprotectedvirtual

Stub to see name in backtrace for easier debugging.

See also
Thread::run()

Reimplemented from fawkes::Thread.

Definition at line 93 of file bumblebee2_thread.h.

References fawkes::Thread::run().


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