threading.h
Go to the documentation of this file.
1 #ifndef H_CAN_THREADING_BASE
2 #define H_CAN_THREADING_BASE
3 
5 #include <boost/thread/thread.hpp>
6 
7 namespace can{
8 
9 class StateWaiter{
10  boost::mutex mutex_;
11  boost::condition_variable cond_;
14  void updateState(const can::State &s){
15  boost::mutex::scoped_lock lock(mutex_);
16  state_ = s;
17  lock.unlock();
18  cond_.notify_all();
19  }
20 public:
21  template<typename InterfaceType> StateWaiter(InterfaceType *interface){
22  state_ = interface->getState();
23  state_listener_ = interface->createStateListener(std::bind(&StateWaiter::updateState, this, std::placeholders::_1));
24  }
25  template<typename DurationType> bool wait(const can::State::DriverState &s, const DurationType &duration){
26  boost::mutex::scoped_lock cond_lock(mutex_);
27  boost::system_time abs_time = boost::get_system_time() + duration;
28  while(s != state_.driver_state)
29  {
30  if(!cond_.timed_wait(cond_lock,abs_time))
31  {
32  return false;
33  }
34  }
35  return true;
36  }
37 };
38 
39 template<typename WrappedInterface> class ThreadedInterface : public WrappedInterface{
40  std::shared_ptr<boost::thread> thread_;
41  void run_thread(){
42  WrappedInterface::run();
43  }
44 public:
45  [[deprecated("provide settings explicitly")]] virtual bool init(const std::string &device, bool loopback) override {
46  #pragma GCC diagnostic push
47  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
48  if(!thread_ && WrappedInterface::init(device, loopback)){
49  StateWaiter waiter(this);
50  thread_.reset(new boost::thread(&ThreadedInterface::run_thread, this));
51  return waiter.wait(can::State::ready, boost::posix_time::seconds(1));
52  }
53  return WrappedInterface::getState().isReady();
54  #pragma GCC diagnostic pop
55  }
56  virtual bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override {
57  if(!thread_ && WrappedInterface::init(device, loopback, settings)){
58  StateWaiter waiter(this);
59  thread_.reset(new boost::thread(&ThreadedInterface::run_thread, this));
60  return waiter.wait(can::State::ready, boost::posix_time::seconds(1));
61  }
62  return WrappedInterface::getState().isReady();
63  }
64  virtual void shutdown(){
65  WrappedInterface::shutdown();
66  if(thread_){
67  thread_->interrupt();
68  thread_->join();
69  thread_.reset();
70  }
71  }
72  void join(){
73  if(thread_){
74  thread_->join();
75  }
76  }
77  virtual ~ThreadedInterface() {}
78  ThreadedInterface(): WrappedInterface() {}
79  template<typename T1> ThreadedInterface(const T1 &t1): WrappedInterface(t1) {}
80  template<typename T1, typename T2> ThreadedInterface(const T1 &t1, const T2 &t2): WrappedInterface(t1, t2) {}
81 
82 };
83 
84 
85 } // namespace can
86 #endif
can::StateInterface::StateListenerConstSharedPtr
StateListener::ListenerConstSharedPtr StateListenerConstSharedPtr
Definition: interface.h:117
can::StateWaiter::cond_
boost::condition_variable cond_
Definition: threading.h:11
can::ThreadedInterface::ThreadedInterface
ThreadedInterface(const T1 &t1)
Definition: threading.h:79
can::ThreadedInterface::join
void join()
Definition: threading.h:72
can::ThreadedInterface::init
virtual bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override
Definition: threading.h:56
can::ThreadedInterface::~ThreadedInterface
virtual ~ThreadedInterface()
Definition: threading.h:77
can::ThreadedInterface::run_thread
void run_thread()
Definition: threading.h:41
can::StateWaiter::state_listener_
can::StateInterface::StateListenerConstSharedPtr state_listener_
Definition: threading.h:12
can::StateWaiter::state_
can::State state_
Definition: threading.h:13
can::StateWaiter
Definition: threading.h:9
can::ThreadedInterface::init
virtual bool init(const std::string &device, bool loopback) override
Definition: threading.h:45
can::ThreadedInterface::thread_
std::shared_ptr< boost::thread > thread_
Definition: threading.h:40
interface.h
can::ThreadedInterface::ThreadedInterface
ThreadedInterface()
Definition: threading.h:78
can::SettingsConstSharedPtr
std::shared_ptr< const Settings > SettingsConstSharedPtr
Definition: settings.h:31
can::StateWaiter::mutex_
boost::mutex mutex_
Definition: threading.h:10
can
Definition: asio_base.h:11
can::ThreadedInterface::ThreadedInterface
ThreadedInterface(const T1 &t1, const T2 &t2)
Definition: threading.h:80
can::StateWaiter::wait
bool wait(const can::State::DriverState &s, const DurationType &duration)
Definition: threading.h:25
can::ThreadedInterface::shutdown
virtual void shutdown()
Definition: threading.h:64
can::State::DriverState
DriverState
Definition: interface.h:88
can::StateWaiter::updateState
void updateState(const can::State &s)
Definition: threading.h:14
can::State::ready
@ ready
Definition: interface.h:89
can::State
Definition: interface.h:86
can::State::driver_state
enum can::State::DriverState driver_state
can::StateWaiter::StateWaiter
StateWaiter(InterfaceType *interface)
Definition: threading.h:21


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Wed Mar 2 2022 00:52:25