Libsockcanpp
A complete C++ wrapper around socketcan.
Loading...
Searching...
No Matches
CanDriver.hpp
Go to the documentation of this file.
1/**
2 * @file CanDriver.hpp
3 * @author Simon Cahill (contact@simonc.eu)
4 * @brief Contains the declarations for the SocketCAN wrapper in C++.
5 * @version 0.1
6 * @date 2020-07-01
7 *
8 * @copyright Copyright (c) 2020-2025 Simon Cahill
9 *
10 * Licensed under the Apache License, Version 2.0 (the "License");
11 * you may not use this file except in compliance with the License.
12 * You may obtain a copy of the License at
13 *
14 * http://www.apache.org/licenses/LICENSE-2.0
15 *
16 * Unless required by applicable law or agreed to in writing, software
17 * distributed under the License is distributed on an "AS IS" BASIS,
18 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
19 * See the License for the specific language governing permissions and
20 * limitations under the License.
21 */
22
23#ifndef LIBSOCKCANPP_INCLUDE_CANDRIVER_HPP
24#define LIBSOCKCANPP_INCLUDE_CANDRIVER_HPP
25
26//////////////////////////////
27// SYSTEM INCLUDES //
28//////////////////////////////
29#include <mutex>
30#include <queue>
31#include <string>
32#include <thread>
33#include <unordered_map>
34
35//////////////////////////////
36// LOCAL INCLUDES //
37//////////////////////////////
38#include "CanId.hpp"
39#include "CanMessage.hpp"
40
41/**
42 * @brief Main library namespace.
43 *
44 * This namespace contains the library's main code.
45 */
46namespace sockcanpp {
47
48 using namespace std::chrono_literals;
49
50 using std::chrono::microseconds;
51 using std::chrono::milliseconds;
52 using std::chrono::nanoseconds;
53 using std::mutex;
54 using std::string;
55 using std::queue;
56 using std::unordered_map;
57
58 using filtermap_t = unordered_map<CanId, uint32_t, CanIdHasher>;
59
60 /**
61 * @brief CanDriver class; handles communication via CAN.
62 *
63 * This class provides the means of easily communicating with other devices via CAN in C++.
64 *
65 * @remarks
66 * This class may be inherited by other applications and modified to suit your needs.
67 */
68 class CanDriver {
69 public: // +++ Static +++
70 static constexpr int32_t CAN_MAX_DATA_LENGTH = 8; //!< The maximum amount of bytes allowed in a single CAN frame
71 static constexpr int32_t CAN_SOCK_RAW = CAN_RAW; //!< The raw CAN protocol
72 static constexpr int32_t CAN_SOCK_SEVEN = 7; //!< A separate CAN protocol, used by certain embedded device OEMs.
73
74 public: // +++ Constructor / Destructor +++
75 CanDriver(const string& canInterface, const int32_t canProtocol, const CanId defaultSenderId = 0); //!< Constructor
76 CanDriver(const string& canInterface, const int32_t canProtocol, const int32_t filterMask, const CanId defaultSenderId = 0);
77 CanDriver(const string& canInterface, const int32_t canProtocol, const filtermap_t& filters, const CanId defaultSenderId = 0);
78 CanDriver() = default;
79 virtual ~CanDriver() { uninitialiseSocketCan(); } //!< Destructor
80
81 public: // +++ Getter / Setter +++
82 CanDriver& setDefaultSenderId(const CanId& id) { this->_defaultSenderId = id; return *this; } //!< Sets the default sender ID
83
84 CanId getDefaultSenderId() const { return this->_defaultSenderId; } //!< Gets the default sender ID
85
86 filtermap_t getFilterMask() const { return this->_canFilterMask; } //!< Gets the filter mask used by this instance
87
88 int32_t getMessageQueueSize() const { return this->_queueSize; } //!< Gets the amount of CAN messages found after last calling waitForMessages()
89 int32_t getSocketFd() const { return this->_socketFd; } //!< The socket file descriptor used by this instance.
90
91 string getCanInterface() const { return this->_canInterface; } //!< The CAN interface used by this instance.
92
93 public: // +++ I/O +++
94 virtual bool waitForMessages(microseconds timeout = 3000us); //!< Waits for CAN messages to appear
95 virtual bool waitForMessages(milliseconds timeout = 3000ms); //!< Waits for CAN messages to appear
96 virtual bool waitForMessages(nanoseconds timeout = 3000ns); //!< Waits for CAN messages to appear
97
98 virtual CanMessage readMessage(); //!< Attempts to read a single message from the bus
99
100 virtual ssize_t sendMessage(const CanMessage& message, bool forceExtended = false); //!< Attempts to send a single CAN message
101 virtual ssize_t sendMessageQueue(queue<CanMessage>& messages, microseconds delay = 20us, bool forceExtended = false); //!< Attempts to send a queue of messages
102 virtual ssize_t sendMessageQueue(queue<CanMessage>& messages, milliseconds delay = 20ms, bool forceExtended = false); //!< Attempts to send a queue of messages
103 virtual ssize_t sendMessageQueue(queue<CanMessage>& messages, nanoseconds delay = 20ns, bool forceExtended = false); //!< Attempts to send a queue of messages
104
105 virtual queue<CanMessage> readQueuedMessages(); //!< Attempts to read all queued messages from the bus
106
107 public: // +++ Socket Management +++
108 virtual void allowCanFdFrames(const bool enabled = true) const; //!< Sets the CAN FD frame option for the interface
109 #ifdef CANXL_XLF
110 virtual void allowCanXlFrames(const bool enabled = true) const; //!< Sets the CAN XL frame option for the interface
111 #endif // CANXL_XLF
112 virtual void joinCanFilters() const; //!< Configures the socket to join the CAN filters
113 virtual void setCanFilterMask(const int32_t mask, const CanId& filterId); //!< Attempts to set a new CAN filter mask to the interface
114 virtual void setCanFilters(const filtermap_t& filters); //!< Sets the CAN filters for the interface
115 virtual void setErrorFilter(const bool enabled = true) const; //!< Sets the error filter for the interface
116 virtual void setReceiveOwnMessages(const bool enabled = true) const; //!< Sets the receive own messages option for the interface
117
118 protected: // +++ Socket Management +++
119 virtual void initialiseSocketCan(); //!< Initialises socketcan
120 virtual void uninitialiseSocketCan(); //!< Uninitialises socketcan
121
122 private: // +++ Member Functions +++
123 virtual CanMessage readMessageLock(bool const lock = true); //!< readMessage deadlock guard
124
125 private: // +++ Variables +++
126
127 CanId _defaultSenderId; //!< The ID to send messages with if no other ID was set.
128
129 filtermap_t _canFilterMask; //!< The bit mask used to filter CAN messages
130
131 int32_t _canProtocol; //!< The protocol used when communicating via CAN
132 int32_t _socketFd{-1}; //!< The CAN socket file descriptor
133 int32_t _queueSize{0}; ///!< The size of the message queue read by waitForMessages()
134 bool _canReadQueueSize{true}; ///!< Is the queue size available
135
136 //!< Mutex for thread-safety.
137 mutex _lock{};
138 mutex _lockSend{};
139
140 string _canInterface; //!< The CAN interface used for communication (e.g. can0, can1, ...)
141
142 };
143
144 /**
145 * @brief Formats a std string object.
146 *
147 * @remarks Yoinked from https://github.com/Beatsleigher/liblogpp :)
148 *
149 * @tparam Args The formatting argument types.
150 * @param format The format string.
151 * @param args The format arguments (strings must be converted to C-style strings!)
152 *
153 * @return string The formatted string.
154 */
155 template<typename... Args>
156 string formatString(const string& format, Args... args) {
157 using std::unique_ptr;
158 auto stringSize = snprintf(nullptr, 0, format.c_str(), args...) + 1; // +1 for \0
159 unique_ptr<char[]> buffer(new char[stringSize]);
160
161 snprintf(buffer.get(), stringSize, format.c_str(), args...);
162
163 return string(buffer.get(), buffer.get() + stringSize - 1); // std::string handles termination for us.
164 }
165
166}
167
168#endif // LIBSOCKCANPP_INCLUDE_CANDRIVER_HPP
CanDriver class; handles communication via CAN.
Definition CanDriver.hpp:68
virtual void allowCanFdFrames(const bool enabled=true) const
Sets the CAN FD frame option for the interface.
static constexpr int32_t CAN_SOCK_SEVEN
A separate CAN protocol, used by certain embedded device OEMs.
Definition CanDriver.hpp:72
virtual void joinCanFilters() const
Configures the socket to join the CAN filters.
CanDriver(const string &canInterface, const int32_t canProtocol, const filtermap_t &filters, const CanId defaultSenderId=0)
Definition CanDriver.cpp:85
int32_t getMessageQueueSize() const
Gets the amount of CAN messages found after last calling waitForMessages()
Definition CanDriver.hpp:88
bool _canReadQueueSize
!< The size of the message queue read by waitForMessages()
virtual void setReceiveOwnMessages(const bool enabled=true) const
Sets the receive own messages option for the interface.
virtual CanMessage readMessage()
Attempts to read a single message from the bus.
filtermap_t getFilterMask() const
Gets the filter mask used by this instance.
Definition CanDriver.hpp:86
CanDriver(const string &canInterface, const int32_t canProtocol, const CanId defaultSenderId=0)
Constructor.
Definition CanDriver.cpp:79
virtual void setErrorFilter(const bool enabled=true) const
Sets the error filter for the interface.
CanDriver(const string &canInterface, const int32_t canProtocol, const int32_t filterMask, const CanId defaultSenderId=0)
Definition CanDriver.cpp:82
virtual ssize_t sendMessageQueue(queue< CanMessage > &messages, milliseconds delay=20ms, bool forceExtended=false)
Attempts to send a queue of messages.
string getCanInterface() const
The CAN interface used by this instance.
Definition CanDriver.hpp:91
virtual void setCanFilters(const filtermap_t &filters)
Sets the CAN filters for the interface.
string _canInterface
The CAN interface used for communication (e.g. can0, can1, ...)
CanId getDefaultSenderId() const
Gets the default sender ID.
Definition CanDriver.hpp:84
CanId _defaultSenderId
The ID to send messages with if no other ID was set.
virtual queue< CanMessage > readQueuedMessages()
Attempts to read all queued messages from the bus.
int32_t _canProtocol
The protocol used when communicating via CAN.
virtual void setCanFilterMask(const int32_t mask, const CanId &filterId)
Attempts to set a new CAN filter mask to the interface.
virtual CanMessage readMessageLock(bool const lock=true)
readMessage deadlock guard
virtual ssize_t sendMessage(const CanMessage &message, bool forceExtended=false)
Attempts to send a single CAN message.
virtual ssize_t sendMessageQueue(queue< CanMessage > &messages, nanoseconds delay=20ns, bool forceExtended=false)
Attempts to send a queue of messages.
int32_t _socketFd
The CAN socket file descriptor.
static constexpr int32_t CAN_SOCK_RAW
The raw CAN protocol.
Definition CanDriver.hpp:71
virtual bool waitForMessages(milliseconds timeout=3000ms)
Waits for CAN messages to appear.
mutex _lock
!< Is the queue size available
CanDriver & setDefaultSenderId(const CanId &id)
Sets the default sender ID.
Definition CanDriver.hpp:82
filtermap_t _canFilterMask
The bit mask used to filter CAN messages.
int32_t getSocketFd() const
The socket file descriptor used by this instance.
Definition CanDriver.hpp:89
virtual void initialiseSocketCan()
Initialises socketcan.
virtual ~CanDriver()
Destructor.
Definition CanDriver.hpp:79
static constexpr int32_t CAN_MAX_DATA_LENGTH
The maximum amount of bytes allowed in a single CAN frame.
Definition CanDriver.hpp:70
virtual bool waitForMessages(nanoseconds timeout=3000ns)
Waits for CAN messages to appear.
virtual bool waitForMessages(microseconds timeout=3000us)
Waits for CAN messages to appear.
virtual ssize_t sendMessageQueue(queue< CanMessage > &messages, microseconds delay=20us, bool forceExtended=false)
Attempts to send a queue of messages.
virtual void uninitialiseSocketCan()
Uninitialises socketcan.
Represents a CAN message that was received.
const string getFrameData() const
const can_frame getRawFrame() const
CanMessage(const struct can_frame frame)
const CanId getCanId() const
An exception that may be thrown when an error occurs while closing a CAN socket.
An exception that may be thrown when an error occurs while closing a CAN socket.
CanException(const string &message, int32_t socket)
An exception that may be thrown when an error occurred while initialising a CAN socket.
An exception that may be thrown when an error occurs while closing a CAN socket.
InvalidSocketException(const string &message, int32_t socket)
Main library namespace.
Definition CanDriver.cpp:56
string formatString(const string &format, Args... args)
Formats a std string object.
Implements a hash function for the CanId type.
Definition CanId.hpp:265
Represents a CAN ID in a simple and easy-to-use manner.
Definition CanId.hpp:61
constexpr canid_t operator*() const
Returns the raw CAN ID value.
Definition CanId.hpp:75