1 #ifndef H_SOCKETCAN_DRIVER 2 #define H_SOCKETCAN_DRIVER 5 #include <boost/bind.hpp> 8 #include <sys/socket.h> 12 #include <linux/can.h> 13 #include <linux/can/raw.h> 14 #include <linux/can/error.h> 25 : loopback_(false), sc_(-1)
32 virtual bool init(
const std::string &device,
bool loopback){
39 int sc = socket( PF_CAN, SOCK_RAW, CAN_RAW );
41 setErrorCode(boost::system::error_code(sc,boost::system::system_category()));
46 strcpy(ifr.ifr_name,
device_.c_str());
47 int ret = ioctl(sc, SIOCGIFINDEX, &ifr);
50 setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
54 can_err_mask_t err_mask =
66 ret = setsockopt(sc, SOL_CAN_RAW, CAN_RAW_ERR_FILTER,
67 &err_mask,
sizeof(err_mask));
70 setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
76 int recv_own_msgs = 1;
77 ret = setsockopt(sc, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &recv_own_msgs,
sizeof(recv_own_msgs));
80 setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
86 struct sockaddr_can addr = {0};
87 addr.can_family = AF_CAN;
88 addr.can_ifindex = ifr.ifr_ifindex;
89 ret = bind( sc, (
struct sockaddr*)&addr,
sizeof(addr) );
92 setErrorCode(boost::system::error_code(ret,boost::system::system_category()));
97 boost::system::error_code ec;
127 if( internal_error & CAN_ERR_TX_TIMEOUT){
128 str +=
"TX timeout (by netdevice driver);";
131 if( internal_error & CAN_ERR_LOSTARB){
132 str +=
"lost arbitration;";
135 if( internal_error & CAN_ERR_CRTL){
136 str +=
"controller problems;";
139 if( internal_error & CAN_ERR_PROT){
140 str +=
"protocol violations;";
143 if( internal_error & CAN_ERR_TRX){
144 str +=
"transceiver status;";
147 if( internal_error & CAN_ERR_BUSOFF){
151 if( internal_error & CAN_ERR_RESTARTED){
152 str +=
"ontroller restarted;";
172 can_frame frame = {0};
174 frame.can_dlc = msg.
dlc;
177 for(
int i=0; i < frame.can_dlc;++i)
178 frame.data[i] = msg.
data[i];
180 boost::system::error_code ec;
181 boost::asio::write(
socket_, boost::asio::buffer(&frame,
sizeof(frame)),boost::asio::transfer_all(), ec);
183 LOG(
"FAILED " << ec);
195 for(
int i=0;i<frame_.can_dlc && i < 8; ++i){
199 if(frame_.can_id & CAN_ERR_FLAG){
200 input_.
id = frame_.can_id & CAN_EFF_MASK;
virtual bool translateError(unsigned int internal_error, std::string &str)
virtual bool init(const std::string &device, bool loopback)
virtual bool doesLoopBack() const
void setInternalError(unsigned int internal_error)
boost::array< value_type, 8 > data
array for 8 data bytes with bounds checking
boost::shared_ptr< SocketCANInterface > SocketCANInterfaceSharedPtr
SocketCANInterface SocketCANDriver
virtual void triggerReadSome()
ThreadedInterface< SocketCANInterface > ThreadedSocketCANInterface
void setErrorCode(const boost::system::error_code &error)
enum can::State::DriverState driver_state
void setDriverState(State::DriverState state)
boost::shared_ptr< ThreadedSocketCANInterface > ThreadedSocketCANInterfaceSharedPtr
virtual bool isReady() const
void readFrame(const boost::system::error_code &error)
void frameReceived(const boost::system::error_code &error)
virtual bool enqueue(const Frame &msg)
boost::shared_ptr< SocketCANDriver > SocketCANDriverSharedPtr
unsigned char dlc
len of data
boost::asio::posix::stream_descriptor socket_