SickBufferMonitor.hh
Go to the documentation of this file.
00001 
00016 #ifndef SICK_BUFFER_MONITOR
00017 #define SICK_BUFFER_MONITOR
00018 
00019 /* Dependencies */
00020 #include <iostream>
00021 #include <pthread.h>
00022 #include "SickException.hh"
00023 
00024 /* Associate the namespace */
00025 namespace SickToolbox {
00026 
00030   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00031   class SickBufferMonitor {
00032 
00033   public:
00034 
00036     SickBufferMonitor( SICK_MONITOR_CLASS * const monitor_instance ) throw( SickThreadException );
00037 
00039     void SetDataStream( const unsigned int sick_fd ) throw( SickThreadException );
00040     
00042     void StartMonitor( const unsigned int sick_fd ) throw( SickThreadException );
00043 
00045     bool GetNextMessageFromMonitor( SICK_MSG_CLASS &sick_message ) throw( SickThreadException );
00046     
00048     void StopMonitor( ) throw( SickThreadException );
00049 
00051     void AcquireDataStream( ) throw( SickThreadException );
00052 
00054     void GetNextMessageFromDataStream( SICK_MSG_CLASS &sick_message );
00055     
00057     void ReleaseDataStream( ) throw( SickThreadException );
00058 
00060     ~SickBufferMonitor( ) throw( SickThreadException );
00061 
00062   protected:
00063 
00065     unsigned int _sick_fd;   
00066     
00068     void _readBytes( uint8_t * const dest_buffer, const int num_bytes_to_read, const unsigned int timeout_value = 0 ) const throw ( SickTimeoutException, SickIOException );       
00069     
00070   private:
00071 
00073     SICK_MONITOR_CLASS *_sick_monitor_instance;
00074 
00076     bool _continue_grabbing;
00077     
00079     pthread_t _monitor_thread_id;
00080 
00082     pthread_mutex_t _container_mutex;
00083 
00085     pthread_mutex_t _stream_mutex;
00086     
00088     SICK_MSG_CLASS _recv_msg_container;      
00089 
00091     void _acquireMessageContainer( ) throw( SickThreadException );
00092 
00094     void _releaseMessageContainer( ) throw( SickThreadException );   
00095 
00097     static void * _bufferMonitorThread( void * thread_args );    
00098     
00099   };
00100 
00105   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00106   SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::SickBufferMonitor( SICK_MONITOR_CLASS * const monitor_instance ) throw( SickThreadException ) :
00107     _sick_monitor_instance(monitor_instance), _continue_grabbing(true), _monitor_thread_id(0) {
00108     
00109     /* Initialize the shared message buffer mutex */
00110     if (pthread_mutex_init(&_container_mutex,NULL) != 0) {
00111       throw SickThreadException("SickBufferMonitor::SickBufferMonitor: pthread_mutex_init() failed!");
00112     }
00113 
00114     /* Initialize the shared data stream mutex */
00115     if (pthread_mutex_init(&_stream_mutex,NULL) != 0) {
00116       throw SickThreadException("SickBufferMonitor::SickBufferMonitor: pthread_mutex_init() failed!");
00117     }
00118     
00119   }
00120 
00125   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00126   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::SetDataStream( const unsigned int sick_fd ) throw ( SickThreadException ) {
00127 
00128     try {
00129     
00130       /* Attempt to acquire the data stream */
00131       AcquireDataStream();
00132       
00133       /* Assign the data stream fd */
00134       _sick_fd = sick_fd;
00135       
00136       /* Attempt to release the data stream */
00137       ReleaseDataStream();
00138       
00139     }
00140 
00141     /* Handle thread exception */
00142     catch(SickThreadException &sick_thread_exception) {
00143       std::cerr << sick_thread_exception.what() << std::endl;
00144     }
00145     
00146     /* A safety net */
00147     catch(...) {
00148       std::cerr << "SickBufferMonitor::SetDataStream: Unknown exception!" << std::endl;
00149       throw;
00150     }
00151     
00152   }
00153   
00158   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00159   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::StartMonitor( const unsigned int sick_fd ) throw ( SickThreadException ) {
00160 
00161     /* Assign the fd associated with the data stream */
00162     _sick_fd = sick_fd;
00163     
00164     /* Start the buffer monitor */
00165     if (pthread_create(&_monitor_thread_id,NULL,SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_bufferMonitorThread,_sick_monitor_instance) != 0) {
00166       throw SickThreadException("SickBufferMonitor::StartMonitor: pthread_create() failed!");
00167     }
00168 
00169     /* Set the flag to continue grabbing data */
00170     _continue_grabbing = true;
00171     
00172   }
00173 
00179   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00180   bool SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::GetNextMessageFromMonitor( SICK_MSG_CLASS &sick_message ) throw( SickThreadException ) {
00181 
00182     bool acquired_message = false;
00183 
00184     try {
00185     
00186       /* Acquire a lock on the message buffer */
00187       _acquireMessageContainer();
00188 
00189       /* Check whether the object is populated */
00190       if (_recv_msg_container.IsPopulated()) {
00191 
00192         /* Copy the shared message */
00193         sick_message = _recv_msg_container;
00194         _recv_msg_container.Clear();
00195         
00196         /* Set the flag indicating success */
00197         acquired_message = true;      
00198       }
00199 
00200       /* Release message container */
00201       _releaseMessageContainer();      
00202 
00203     }
00204 
00205     /* Handle a thread exception */
00206     catch(SickThreadException &sick_thread_exception) {
00207       std::cerr << sick_thread_exception.what() << std::endl;
00208       throw;
00209     }
00210 
00211     /* Handle an unknown exception */
00212     catch(...) {
00213       std::cerr << "SickBufferMonitor::CheckMessageContainer: Unknown exception!" << std::endl;
00214       throw;
00215     }
00216     
00217     /* Return the flag */
00218     return acquired_message;    
00219   }
00220   
00225   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00226   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::StopMonitor( ) throw ( SickThreadException ) {
00227 
00228     try {
00229 
00230       /* Return results from the thread */
00231       void *monitor_result = NULL;     
00232       
00233       /* Tell the thread to quit working */
00234       AcquireDataStream();      
00235       _continue_grabbing = false;
00236       ReleaseDataStream();
00237 
00238       /* Wait for the buffer monitor to exit */
00239       if (pthread_join(_monitor_thread_id,&monitor_result) != 0) {
00240         throw SickThreadException("SickBufferMonitor::StopMonitor: pthread_join() failed!");      
00241       }
00242 
00243     }
00244 
00245     /* Handle thread exception */
00246     catch(SickThreadException &sick_thread_exception) {
00247       std::cerr << sick_thread_exception.what() << std::endl;
00248     }
00249     
00250     /* A safety net */
00251     catch(...) {
00252       std::cerr << "SickBufferMonitor::StopMonitor: Unknown exception!" << std::endl;
00253       throw;
00254     }
00255     
00256   }
00257 
00261   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00262   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::AcquireDataStream( ) throw( SickThreadException ) {
00263 
00264     /* Attempt to lock the stream mutex */
00265     if (pthread_mutex_lock(&_stream_mutex) != 0) {
00266       throw SickThreadException("SickBufferMonitor::AcquireDataStream: pthread_mutex_lock() failed!");
00267     }
00268     
00269   }
00270 
00274   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00275   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::ReleaseDataStream( ) throw( SickThreadException ) {
00276 
00277     /* Attempt to lock the stream mutex */
00278     if (pthread_mutex_unlock(&_stream_mutex) != 0) {
00279       throw SickThreadException("SickBufferMonitor::ReleaseDataStream: pthread_mutex_unlock() failed!");
00280     }
00281     
00282   }
00283   
00287   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00288   SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::~SickBufferMonitor( ) throw( SickThreadException ) {
00289 
00290     /* Destroy the message container mutex */
00291     if (pthread_mutex_destroy(&_container_mutex) != 0) {
00292       throw SickThreadException("SickBufferMonitor::~SickBufferMonitor: pthread_mutex_destroy() failed!");
00293     }
00294 
00295     /* Destroy the data stream container mutex */
00296     if (pthread_mutex_destroy(&_stream_mutex) != 0) {
00297       throw SickThreadException("SickBufferMonitor::~SickBufferMonitor: pthread_mutex_destroy() failed!");
00298     }
00299     
00300   }
00301 
00305   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00306   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_acquireMessageContainer( ) throw( SickThreadException ) {
00307 
00308     /* Lock the mutex */
00309     if (pthread_mutex_lock(&_container_mutex) != 0) {
00310       throw SickThreadException("SickBufferMonitor::_acquireMessageContainer: pthread_mutex_lock() failed!");
00311     }   
00312   
00313   }
00314 
00318   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00319   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_releaseMessageContainer( ) throw( SickThreadException ) {
00320 
00321     /* Unlock the mutex */
00322     if (pthread_mutex_unlock(&_container_mutex) != 0) {
00323       throw SickThreadException("SickBufferMonitor::_releaseMessageContainer: pthread_mutex_unlock() failed!");
00324     }   
00325     
00326   }
00327 
00335   template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00336   void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_readBytes( uint8_t * const dest_buffer, const int num_bytes_to_read, const unsigned int timeout_value ) const
00337     throw ( SickTimeoutException, SickIOException ) {
00338     
00339     /* Some helpful variables */
00340     int num_bytes_read = 0;
00341     int total_num_bytes_read = 0;
00342     int num_active_files = 0;
00343     
00344     struct timeval timeout_val;                     // This structure will be used for setting our timeout values
00345     fd_set file_desc_set;                           // File descriptor set for monitoring I/O    
00346     
00347     /* Attempt to fetch the bytes */
00348     while ( total_num_bytes_read < num_bytes_to_read ) {
00349       
00350       /* Initialize and set the file descriptor set for select */
00351       FD_ZERO(&file_desc_set);
00352       FD_SET(_sick_fd,&file_desc_set);
00353       
00354       /* Setup the timeout structure */
00355       memset(&timeout_val,0,sizeof(timeout_val));   // Initialize the buffer
00356       timeout_val.tv_usec = timeout_value;          // Wait for specified time before throwing a timeout
00357 
00358       /* Wait for the OS to tell us that data is waiting! */
00359       num_active_files = select(getdtablesize(),&file_desc_set,0,0,(timeout_value > 0) ? &timeout_val : 0);
00360       
00361       /* Figure out what to do based on the output of select */
00362       if (num_active_files > 0) {
00363         
00364         /* A file is ready for reading!
00365          *
00366          * NOTE: The following conditional is just a sanity check. Since
00367          *       the file descriptor set only contains the sick device fd,
00368          *       it likely unnecessary to use FD_ISSET
00369          */
00370         if (FD_ISSET(_sick_fd,&file_desc_set)) {
00371           
00372           /* Read a single byte from the stream! */
00373           num_bytes_read = read(_sick_fd,&dest_buffer[total_num_bytes_read],1);
00374 
00375           /* Decide what to do based on the output of read */
00376           if (num_bytes_read > 0) { //Update the number of bytes read so far
00377             total_num_bytes_read += num_bytes_read;
00378           }
00379           else {
00380             /* If this happens, something is wrong */
00381             throw SickIOException("SickBufferMonitor::_readBytes: read() failed!");
00382           }       
00383           
00384         }
00385         
00386       }
00387       else if (num_active_files == 0) {
00388         
00389         /* A timeout has occurred! */
00390         throw SickTimeoutException("SickBufferMonitor::_readBytes: select() timeout!"); 
00391 
00392       }
00393       else {
00394         
00395         /* An error has occurred! */
00396         throw SickIOException("SickBufferMonitor::_readBytes: select() failed!");       
00397 
00398       }
00399       
00400     }
00401     
00402   }
00403   
00408   template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS >
00409   void * SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_bufferMonitorThread( void * thread_args ) {
00410     
00411     /* Declare a Sick LD receive object */
00412     SICK_MSG_CLASS curr_message;
00413     
00414     /* Acquire the Sick device instance */
00415     SICK_MONITOR_CLASS *buffer_monitor = (SICK_MONITOR_CLASS *)thread_args;
00416 
00417     /* The main thread control loop */
00418     for (;;) {
00419 
00420       try {
00421 
00422         /* Reset the sick message object */
00423         curr_message.Clear();   
00424 
00425         /* Acquire the most recent message */
00426         buffer_monitor->AcquireDataStream();      
00427         
00428         if (!buffer_monitor->_continue_grabbing) { // should the thread continue grabbing
00429           buffer_monitor->ReleaseDataStream();
00430           break;
00431         }
00432 
00433         buffer_monitor->GetNextMessageFromDataStream(curr_message);
00434         buffer_monitor->ReleaseDataStream();
00435         
00436         /* Update message container contents */
00437         buffer_monitor->_acquireMessageContainer();     
00438         buffer_monitor->_recv_msg_container = curr_message;
00439         buffer_monitor->_releaseMessageContainer();
00440 
00441       }
00442 
00443       /* Make sure there wasn't a serious error reading from the buffer */
00444       catch(SickIOException &sick_io_exception) {
00445         std::cerr << sick_io_exception.what() << std::endl;
00446       }
00447 
00448       /* Catch any thread exceptions */
00449       catch(SickThreadException &sick_thread_exception) {
00450         std::cerr << sick_thread_exception.what() << std::endl;
00451       }
00452       
00453       /* A failsafe */
00454       catch(...) {
00455         std::cerr << "SickBufferMonitor::_bufferMonitorThread: Unknown exception!" << std::endl;
00456       }
00457 
00458       /* sleep a bit! */
00459       usleep(1000);
00460       
00461     }    
00462 
00463     /* Thread is done */
00464     return NULL;
00465     
00466   }
00467   
00468 } /* namespace SickToolbox */
00469 
00470 #endif /* SICK_BUFFER_MONITOR */


asr_mild_base_laserscanner
Author(s): Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Reckling Reno
autogenerated on Thu Jun 6 2019 21:02:16