19 boost::mutex::scoped_lock lock(mutex_);
27 :
Layer(device +
" Layer"), driver_(driver), device_(device), loopback_(loopback), settings_(settings) { assert(driver_); }
30 :
Layer(device +
" Layer"), driver_(driver), device_(device), loopback_(loopback), settings_(
can::NoSettings::create()) { assert(driver_); }
33 if(current_state >
Init){
34 if(!driver_->getState().isReady()) status.
error(
"CAN not ready");
38 if(current_state >
Init){
39 if(!driver_->getState().isReady()) status.
error(
"CAN not ready");
46 report.
error(
"CAN layer not ready");
55 if(driver_->translateError(s.
internal_error, desc)) report.
add(
"internal_error_desc", desc);
56 std::stringstream sstr;
59 boost::mutex::scoped_lock lock(mutex_);
60 for(
size_t i=0; i < last_error_.
dlc; ++i){
61 sstr << (
unsigned int) last_error_.
data[i] <<
" ";
64 report.
add(
"can_error_frame", sstr.str());
72 status.
warn(
"CAN thread already running");
73 }
else if(!driver_->init(device_, loopback_, settings_)) {
74 status.
error(
"CAN init failed");
82 status.
error(
"CAN init timed out");
85 if(!driver_->getState().isReady()){
86 status.
error(
"CAN is not ready");
91 error_listener_.reset();
94 status.
warn(
"CAN shutdown timed out");
106 if(!driver_->getState().isReady()){
std::array< value_type, 8 > data
CANLayer(const can::DriverInterfaceSharedPtr &driver, const std::string &device, bool loopback)
std::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
#define ROSCANOPEN_ERROR(name, args)
const void warn(const std::string &r)
virtual void handleRecover(LayerStatus &status)
const std::string device_
can::DriverInterfaceSharedPtr driver_
virtual void handleInit(LayerStatus &status)
can::FrameListenerConstSharedPtr error_listener_
virtual bool isReady() const
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
enum can::State::DriverState driver_state
std::shared_ptr< const Settings > SettingsConstSharedPtr
virtual void handleWrite(LayerStatus &status, const LayerState ¤t_state)
void handleFrame(const can::Frame &msg)
virtual void handleHalt(LayerStatus &status)
std::shared_ptr< boost::thread > thread_
virtual void handleShutdown(LayerStatus &status)
virtual void handleRead(LayerStatus &status, const LayerState ¤t_state)
void add(const std::string &key, const T &value)
can::SettingsConstSharedPtr settings_
const void error(const std::string &r)
CANLayer(const can::DriverInterfaceSharedPtr &driver, const std::string &device, bool loopback, can::SettingsConstSharedPtr settings)
virtual void handleDiag(LayerReport &report)
unsigned int internal_error
boost::system::error_code error_code