threading.h
Go to the documentation of this file.
00001 #ifndef H_CAN_THREADING_BASE
00002 #define H_CAN_THREADING_BASE
00003 
00004 #include <socketcan_interface/interface.h>
00005 #include <boost/thread/thread.hpp>
00006 #include <boost/bind.hpp>
00007 
00008 namespace can{
00009 
00010 
00011 class StateWaiter{
00012     boost::mutex mutex_;
00013     boost::condition_variable cond_;
00014     can::StateInterface::StateListener::Ptr state_listener_;
00015     can::State state_;
00016     void updateState(const can::State &s){
00017         boost::mutex::scoped_lock lock(mutex_);
00018         state_ = s;
00019         lock.unlock();
00020         cond_.notify_all();
00021     }
00022 public:
00023     template<typename InterfaceType> StateWaiter(InterfaceType *interface){
00024         state_ = interface->getState();
00025         state_listener_ = interface->createStateListener(can::StateInterface::StateDelegate(this, &StateWaiter::updateState));
00026     }
00027     template<typename DurationType> bool wait(const can::State::DriverState &s, const DurationType &duration){
00028         boost::mutex::scoped_lock cond_lock(mutex_);
00029         boost::system_time abs_time = boost::get_system_time() + duration;
00030         while(s != state_.driver_state)
00031         {
00032             if(!cond_.timed_wait(cond_lock,abs_time))
00033             {
00034                 return false;
00035             }
00036         }
00037         return true;
00038     }
00039 };
00040 
00041 template<typename WrappedInterface> class ThreadedInterface : public WrappedInterface{
00042     boost::shared_ptr<boost::thread> thread_;
00043     void run_thread(){
00044         WrappedInterface::run();
00045     }
00046 public:
00047     virtual bool init(const std::string &device, bool loopback) {
00048         if(!thread_ && WrappedInterface::init(device, loopback)){
00049             StateWaiter waiter(this);
00050             thread_.reset(new boost::thread(&ThreadedInterface::run_thread, this));
00051             return waiter.wait(can::State::ready, boost::posix_time::seconds(1));
00052         }
00053         return WrappedInterface::getState().isReady();
00054     }
00055     virtual void shutdown(){
00056         WrappedInterface::shutdown();
00057         if(thread_){
00058             thread_->interrupt();
00059             thread_->join();
00060             thread_.reset();
00061         }
00062     }
00063     void join(){
00064         if(thread_){
00065             thread_->join();
00066         }
00067     }
00068     virtual ~ThreadedInterface() {}
00069     ThreadedInterface(): WrappedInterface() {}
00070     template<typename T1> ThreadedInterface(const T1 &t1): WrappedInterface(t1) {}
00071     template<typename T1, typename T2> ThreadedInterface(const T1 &t1, const T2 &t2): WrappedInterface(t1, t2) {}
00072     
00073 };
00074 
00075 
00076 } // namespace can
00077 #endif


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 20:43:53