1 #ifndef H_CAN_THREADING_BASE 2 #define H_CAN_THREADING_BASE 5 #include <boost/thread/thread.hpp> 11 boost::condition_variable
cond_;
15 boost::mutex::scoped_lock lock(mutex_);
21 template<
typename InterfaceType>
StateWaiter(InterfaceType *interface){
22 state_ = interface->getState();
26 boost::mutex::scoped_lock cond_lock(mutex_);
27 boost::system_time abs_time = boost::get_system_time() + duration;
30 if(!cond_.timed_wait(cond_lock,abs_time))
39 template<
typename WrappedInterface>
class ThreadedInterface :
public WrappedInterface{
42 WrappedInterface::run();
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)){
53 return WrappedInterface::getState().isReady();
54 #pragma GCC diagnostic pop 57 if(!thread_ && WrappedInterface::init(device, loopback, settings)){
62 return WrappedInterface::getState().isReady();
65 WrappedInterface::shutdown();
80 template<
typename T1,
typename T2>
ThreadedInterface(
const T1 &t1,
const T2 &t2): WrappedInterface(t1, t2) {}
StateListener::ListenerConstSharedPtr StateListenerConstSharedPtr
bool wait(const can::State::DriverState &s, const DurationType &duration)
boost::condition_variable cond_
StateWaiter(InterfaceType *interface)
ThreadedInterface(const T1 &t1)
enum can::State::DriverState driver_state
virtual ~ThreadedInterface()
std::shared_ptr< const Settings > SettingsConstSharedPtr
virtual bool init(const std::string &device, bool loopback, SettingsConstSharedPtr settings) override
ThreadedInterface(const T1 &t1, const T2 &t2)
virtual bool init(const std::string &device, bool loopback) override
can::StateInterface::StateListenerConstSharedPtr state_listener_
void updateState(const can::State &s)
std::shared_ptr< boost::thread > thread_