CanUsb.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2020, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 #include <lusb/UsbDevice.h>
37 #include <string.h> // memcpy() and memset()
38 #include <sstream>
39 
40 // Protocol definition
41 #include "UsbCanMessages.h"
42 
43 #include <queue>
44 class TxQueue
45 {
46 public:
47  TxQueue(size_t max_size) : max_size_(max_size) {}
48  ~TxQueue() {}
49  inline bool empty() const { return queue_.empty(); }
50  inline size_t size() const { return queue_.size(); }
51  inline MessageBuffer& front() { return queue_.front(); }
52  inline const MessageBuffer& front() const { return queue_.front(); }
53  inline MessageBuffer& back() { return queue_.back(); }
54  inline const MessageBuffer& back() const { return queue_.back(); }
55  inline bool push(const MessageBuffer& __x) {
56  if (queue_.size() < max_size_) {
57  queue_.push(__x);
58  return true;
59  }
60  return false;
61  }
62  inline void pop() { queue_.pop(); }
63  inline size_t maxSize() const { return max_size_; }
64 private:
65  size_t max_size_;
66  std::queue<MessageBuffer> queue_;
67 };
68 
69 namespace dataspeed_can_usb
70 {
71 
72 CanUsb::CanUsb(lusb::UsbDevice *dev) : ready_(false), heap_dev_(false), dev_(dev), recv_callback_(NULL), version_major_(0), version_minor_(0), version_build_(0), version_comms_(0), serial_number_(0), num_channels_(0)
73 {
74  if (!dev_) {
76  heap_dev_ = true;
77  }
78  queue_ = new TxQueue(100);
79 }
81 {
82  if (dev_) {
83  if (dev_->isOpen()) {
85  dev_->close();
86  }
87  if (heap_dev_) {
88  delete dev_;
89  }
90  dev_ = NULL;
91  }
92  if (queue_) {
93  delete queue_;
94  queue_ = NULL;
95  }
96 }
97 
98 bool CanUsb::configure(const std::string &mac)
99 {
100  if (readVersion()) {
101  if (getNumChannels()) {
102  if (mac.empty() || mac_addr_.match(mac)) {
103  dev_->startBulkReadThread(boost::bind(&CanUsb::recvStream, this, _1, _2), STREAM_ENDPOINT);
104  ready_ = true;
105  return true;
106  }
107  }
108  }
109  return false;
110 }
111 bool CanUsb::open(const std::string &mac)
112 {
113  if (!isOpen()) {
114  if (!dev_->isOpen()) {
115  if (mac.empty()) {
116  if (dev_->open()) {
117  if (configure()) {
118  return true;
119  }
120  }
121  dev_->close();
122  } else {
123  std::vector<lusb::UsbDevice::Location> list;
124  dev_->listDevices(list);
125  for (size_t i = 0; i < list.size(); i++) {
126  if (dev_->open(list[i])) {
127  if (configure(mac)) {
128  return true;
129  }
130  }
131  dev_->close();
132  }
133  }
134  } else {
135  if (configure()) {
136  return true;
137  }
138  }
139  }
140  return isOpen();
141 }
143 {
144  if (ready_) {
145  if (dev_->isOpen()) {
146  return true;
147  } else {
148  ready_ = false;
149  }
150  }
151  return false;
152 }
154 {
156  dev_->close();
157  ready_ = false;
158 }
159 
161 {
162  ConfigPacket packet;
163  packet.msg_id = USB_ID_VERSION;
164  if (writeConfig(&packet, sizeof(packet.msg_id))) {
165  int len = readConfig(&packet, sizeof(packet));
166  if ((len >= (int)sizeof(packet.version) - (int)sizeof(packet.version.mac_addr)) && (packet.msg_id == USB_ID_VERSION)) {
167  version_major_ = packet.version.firmware.major;
168  version_minor_ = packet.version.firmware.minor;
169  version_build_ = packet.version.firmware.build;
170  version_comms_ = packet.version.comms;
171  serial_number_ = packet.version.serial_number;
172  mac_addr_ = (len >= (int)sizeof(packet.version)) ? MacAddr(packet.version.mac_addr) : MacAddr();
173  return true;
174  }
175  }
176  return false;
177 }
178 
180 {
181  ConfigPacket packet;
182  packet.msg_id = USB_ID_NUM_CHANNELS;
183  if (writeConfig(&packet, sizeof(packet.msg_id))) {
184  int len = readConfig(&packet, sizeof(packet));
185  if ((len >= (int)sizeof(packet.num_channels)) && (packet.msg_id == USB_ID_NUM_CHANNELS)) {
186  num_channels_ = packet.num_channels.num_channels;
187  return true;
188  }
189  }
190  return false;
191 }
192 
193 void CanUsb::recvStream(const void *data, int size)
194 {
195  if (recv_callback_) {
196  const MessageBuffer *ptr = ((StreamPacket*)data)->msg;
197  while (size >= (int)sizeof(*ptr)) {
198  size -= sizeof(*ptr);
199  recv_callback_(ptr->channel, ptr->id, ptr->extended, ptr->dlc, ptr->data);
200  ptr++;
201  }
202  }
203 }
204 
206 {
207  ConfigPacket packet;
208  packet.msg_id = USB_ID_REBOOT;
209  if (writeConfig(&packet, sizeof(packet.msg_id))) {
210  closeDevice();
211  return true;
212  }
213  return false;
214 }
215 
217 {
218  ConfigPacket packet;
219  packet.msg_id = USB_ID_RESET;
220  if (writeConfig(&packet, sizeof(packet.msg_id))) {
221  int len = readConfig(&packet, sizeof(packet), USB_DEFAULT_TIMEOUT);
222  if ((len >= (int)sizeof(packet.msg_id)) && (packet.msg_id == USB_ID_RESET)) {
223  return true;
224  }
225  }
226  return false;
227 }
228 
229 bool CanUsb::setBitrate(unsigned int channel, uint32_t bitrate, uint8_t mode)
230 {
231  ConfigPacket packet;
232  packet.msg_id = USB_ID_SET_BUS_CFG;
233  packet.bus_cfg.channel = channel;
234  packet.bus_cfg.bitrate = bitrate;
235  packet.bus_cfg.mode = mode;
236  if (writeConfig(&packet, sizeof(packet.bus_cfg))) {
237  int len = readConfig(&packet, sizeof(packet), USB_DEFAULT_TIMEOUT);
238  if ((len >= (int)sizeof(packet.bus_cfg)) && (packet.msg_id == USB_ID_GET_BUS_CFG)) {
239  return true;
240  }
241  }
242  return false;
243 }
244 
245 bool CanUsb::addFilter(unsigned int channel, uint32_t mask, uint32_t match)
246 {
247  ConfigPacket packet;
248  packet.msg_id = USB_ID_SET_FILTER;
249  packet.filter.channel = channel;
250  packet.filter.mask = mask;
251  packet.filter.match = match;
252  if (writeConfig(&packet, sizeof(packet.filter))) {
253  int len = readConfig(&packet, sizeof(packet), USB_DEFAULT_TIMEOUT);
254  if ((len >= (int)sizeof(packet.filter)) && (packet.msg_id == USB_ID_SET_FILTER)) {
255  if (packet.filter.success) {
256  return true;
257  }
258  }
259  }
260  return false;
261 }
262 
263 bool CanUsb::getStats(std::vector<uint32_t> &rx_drops, std::vector<uint32_t> &tx_drops,
264  std::vector<uint8_t> &rx_errors, std::vector<uint8_t> &tx_errors, bool)
265 {
266  // TODO: implement clear functionality (last param)
267  ConfigPacket packet;
268  packet.msg_id = USB_ID_GET_STATS;
269  if (writeConfig(&packet, sizeof(packet.bus_cfg))) {
270  int len = readConfig(&packet, sizeof(packet), USB_DEFAULT_TIMEOUT);
271  if ((len >= (int)sizeof(packet.stats)) && (packet.msg_id == USB_ID_GET_STATS)) {
272  unsigned int size = std::min(num_channels_, (unsigned int)MAX_CHANNELS);
273  rx_drops.resize(size);
274  tx_drops.resize(size);
275  rx_errors.resize(size);
276  tx_errors.resize(size);
277  for (unsigned int i = 0; i < size; i++) {
278  rx_drops[i] = packet.stats.rx_drops[i];
279  tx_drops[i] = packet.stats.tx_drops[i];
280  rx_errors[i] = packet.stats.rx_errors[i];
281  tx_errors[i] = packet.stats.tx_errors[i];
282  }
283  return true;
284  }
285  }
286  return false;
287 }
288 
289 bool CanUsb::getTimeStamp(uint32_t &timestamp)
290 {
291  ConfigPacket packet;
292  packet.msg_id = USB_ID_GET_TIME;
293  if (writeConfig(&packet, sizeof(packet.msg_id))) {
294  int len = readConfig(&packet, sizeof(packet));
295  if ((len >= (int)sizeof(packet.time)) && (packet.msg_id == USB_ID_GET_TIME)) {
296  timestamp = packet.time.stamp;
297  return true;
298  }
299  }
300  return false;
301 }
302 
303 void CanUsb::sendMessage(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8], bool flush)
304 {
305  MessageBuffer msg;
306  msg.headerWord[0] = 0;
307  msg.headerWord[1] = 0;
308  msg.id = id;
309  msg.extended = extended ? 1 : 0;
310  msg.channel = channel;
311  msg.dlc = dlc;
312  memcpy(msg.data, data, 8);
313  queue_->push(msg);
314  if (flush || (queue_->size() >= sizeof(StreamPacket) / sizeof(MessageBuffer))) {
315  flushMessages();
316  }
317 }
319 {
320  if (!queue_->empty()) {
321  unsigned int num = std::min(queue_->size(), sizeof(StreamPacket) / sizeof(MessageBuffer));
322  if (writeStream(&queue_->front(), num * sizeof(MessageBuffer))) {
323  while (num--) {
324  queue_->pop();
325  }
326  }
327  }
328 }
329 
330 bool CanUsb::writeConfig(const void * data, int size)
331 {
332  return writeConfig(data, size, USB_DEFAULT_TIMEOUT);
333 }
334 int CanUsb::readConfig(void * data, int size)
335 {
336  return readConfig(data, size, USB_DEFAULT_TIMEOUT);
337 }
338 bool CanUsb::writeConfig(const void * data, int size, int timeout)
339 {
340  if (!dev_->bulkWrite(data, size, CONFIGURATION_ENDPOINT, timeout)) {
341  return false;
342  }
343  return true;
344 }
345 int CanUsb::readConfig(void * data, int size, int timeout)
346 {
347  int len = dev_->bulkRead(data, size, CONFIGURATION_ENDPOINT, timeout);
348  if (len < 0) {
349  return -1;
350  }
351  return len;
352 }
353 
354 bool CanUsb::writeStream(const void * data, int size)
355 {
356  if (!dev_->bulkWrite(data, size, STREAM_ENDPOINT, USB_DEFAULT_TIMEOUT)) {
357  return false;
358  }
359  return true;
360 }
361 int CanUsb::readStream(void * data, int size)
362 {
363  int len = dev_->bulkRead(data, size, STREAM_ENDPOINT, USB_DEFAULT_TIMEOUT);
364  if (len < 0) {
365  return -1;
366  }
367  return len;
368 }
369 
370 std::string CanUsb::version() const
371 {
372  std::stringstream s;
373  s << version_major_ << "." << version_minor_ << "." << version_build_ << "-" << version_comms_;
374  return s.str();
375 }
376 
377 } // namespace dataspeed_can_usb
378 
size_t maxSize() const
Definition: CanUsb.cpp:63
bool match(const MacAddr &other) const
Definition: MacAddr.h:76
size_t size() const
Definition: CanUsb.cpp:50
struct PACK_ATTRIB::PACK_ATTRIB bus_cfg
#define CONFIGURATION_ENDPOINT
#define STREAM_ENDPOINT
const MessageBuffer & back() const
Definition: CanUsb.cpp:54
std::string version() const
Definition: CanUsb.cpp:370
void stopBulkReadThread(unsigned char endpoint)
XmlRpcServer s
void sendMessage(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8], bool flush=true)
Definition: CanUsb.cpp:303
~TxQueue()
Definition: CanUsb.cpp:48
int readConfig(void *data, int size)
Definition: CanUsb.cpp:334
lusb::UsbDevice * dev_
Definition: CanUsb.h:110
#define USB_VID
struct PACK_ATTRIB::PACK_ATTRIB stats
int bulkRead(void *data, int size, unsigned char endpoint, int timeout)
struct PACK_ATTRIB::PACK_ATTRIB num_channels
bool getTimeStamp(uint32_t &timestamp)
Definition: CanUsb.cpp:289
unsigned int num_channels_
Definition: CanUsb.h:118
bool writeConfig(const void *data, int size)
Definition: CanUsb.cpp:330
MessageBuffer msg[4]
struct PACK_ATTRIB::PACK_ATTRIB time
bool isOpen() const
static const int USB_DEFAULT_TIMEOUT
Definition: CanUsb.h:57
bool open(const Location &location=Location())
bool getStats(std::vector< uint32_t > &rx_drops, std::vector< uint32_t > &tx_drops, std::vector< uint8_t > &rx_errors, std::vector< uint8_t > &tx_errors, bool clear=false)
Definition: CanUsb.cpp:263
void recvStream(const void *data, int size)
Definition: CanUsb.cpp:193
void pop()
Definition: CanUsb.cpp:62
const MessageBuffer & front() const
Definition: CanUsb.cpp:52
bool open(const std::string &mac=std::string())
Definition: CanUsb.cpp:111
struct PACK_ATTRIB::PACK_ATTRIB version
bool writeStream(const void *data, int size)
Definition: CanUsb.cpp:354
MessageBuffer & front()
Definition: CanUsb.cpp:51
uint8_t msg_id
static const unsigned int MAX_CHANNELS
Definition: CanUsb.h:58
MessageBuffer & back()
Definition: CanUsb.cpp:53
int readStream(void *data, int size)
Definition: CanUsb.cpp:361
size_t max_size_
Definition: CanUsb.cpp:65
#define USB_PID
struct PACK_ATTRIB StreamPacket
TxQueue(size_t max_size)
Definition: CanUsb.cpp:47
#define USB_MI
bool empty() const
Definition: CanUsb.cpp:49
void startBulkReadThread(Callback callback, unsigned char endpoint)
bool addFilter(unsigned int channel, uint32_t mask, uint32_t match)
Definition: CanUsb.cpp:245
std::queue< MessageBuffer > queue_
Definition: CanUsb.cpp:66
bool bulkWrite(const void *data, int size, unsigned char endpoint, int timeout)
union PACK_ATTRIB MessageBuffer
bool configure(const std::string &mac=std::string())
Definition: CanUsb.cpp:98
struct PACK_ATTRIB::PACK_ATTRIB filter
void listDevices(std::vector< Location > &list) const
bool setBitrate(unsigned int channel, uint32_t bitrate, uint8_t mode=0)
Definition: CanUsb.cpp:229
bool push(const MessageBuffer &__x)
Definition: CanUsb.cpp:55


dataspeed_can_usb
Author(s): Kevin Hallenbeck
autogenerated on Thu Jul 9 2020 03:42:00