====== SocketCAN DUNE implementation ====== CANbus support was not present in DUNE, and therefore had to be added. Since the Raspberry Pi on the Otter is using Linux, we can use the SocketCAN package, which comes with the Linux kernel by default. ===== Interface in DUNE ===== Many DUNE tasks use an interface defined by ''%%IO::Handle%%'', and so does this CAN implementation. This means that there will be little difference between using CAN or Serial in DUNE. The biggest difference is that CAN uses addresses, and so must have functions to set and get these. The ''%%Poll::poll%%'' functionality also works, and makes it possible to read with timeout from the CAN bus. Reading it without checking will result in the task waiting until a CAN message is received. ==== Example of reading ==== if (Poll::poll(*m_can, 0.01)) { m_can->readString(m_can_bfr, sizeof(m_can_bfr)); // Read from CAN bus id = m_can->getRXID(); // Address of the most previously read message. Must be called after a read to yield desired data. } Here, ''%%m_can_bfr%%'' is a char array that is used to store the data read from CAN. ==== Example of writing ==== m_can_bfr[0] = 0x4f; m_can_bfr[1] = 0x74; m_can_bfr[2] = 0x74; m_can_bfr[3] = 0x65; m_can_bfr[4] = 0x72; m_can->setTXID(0x0000feab); // If all messages is sent with the same ID, this only needs to be called once m_can->write(m_can_bfr, 5); // Write 5 chars to CAN with the previously set ID Here, ''%%m_can_bfr%%'' still is a char array. ==== Example of initializing a SocketCAN instance ==== The CAN implementation uses ''%%DUNE/System/Error.hpp%%'' to send errors when something goes wrong while initializing SocketCAN. Here is an example on how to initialize SocketCAN while catching eventual errors: try { m_can = new Hardware::SocketCAN(m_args.can_dev, SocketCAN::CAN_BASIC_EFF); } catch(std::runtime_error& e) { cri(DTR("Could not open CAN: %s"), e.what()); } ===== Useful links ===== * [[https://www.kernel.org/doc/Documentation/networking/can.txt|Linux kernel documentation on CAN]]