CanUsb.h
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 
35 #ifndef _DATASPEED_CAN_USB_CAN_USB_H
36 #define _DATASPEED_CAN_USB_CAN_USB_H
37 
38 #include <stdint.h>
39 #include <vector>
40 #include <boost/bind.hpp>
41 #include <boost/function.hpp>
43 
44 namespace lusb
45 {
46 class UsbDevice;
47 }
48 
49 class TxQueue;
50 
51 namespace dataspeed_can_usb
52 {
53 
54 class CanUsb
55 {
56 public:
57  static const int USB_DEFAULT_TIMEOUT = 10;
58  static const unsigned int MAX_CHANNELS = 4;
59  static const unsigned int MAX_FILTERS = 32;
60 
61  CanUsb(lusb::UsbDevice *dev = NULL);
62  ~CanUsb();
63 
64  std::string version() const;
65  uint16_t versionMajor() const { return version_major_; }
66  uint16_t versionMinor() const { return version_minor_; }
67  uint16_t versionBuild() const { return version_build_; }
68  uint16_t versionComms() const { return version_comms_; }
69  uint32_t serialNumber() const { return serial_number_; }
70  MacAddr macAddr() const { return mac_addr_; }
71  unsigned int numChannels() const { return num_channels_; }
72 
73  bool open(const std::string &mac = std::string());
74  bool isOpen();
75  void closeDevice();
76 
77  bool reboot();
78  bool reset();
79  bool setBitrate(unsigned int channel, uint32_t bitrate, uint8_t mode = 0);
80  bool addFilter(unsigned int channel, uint32_t mask, uint32_t match);
81  bool getStats(std::vector<uint32_t> &rx_drops, std::vector<uint32_t> &tx_drops,
82  std::vector<uint8_t> &rx_errors, std::vector<uint8_t> &tx_errors, bool clear = false);
83  bool getTimeStamp(uint32_t &timestamp);
84 
85  void sendMessage(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8], bool flush = true);
86  void flushMessages();
87 
88  typedef boost::function<void(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8])> Callback;
89  void setRecvCallback(const Callback &callback) {
90  recv_callback_ = callback;
91  }
92 
93 private:
94  bool readVersion();
95  bool getNumChannels();
96  bool configure(const std::string &mac = std::string());
97 
98  void recvStream(const void *data, int size);
99 
100  bool writeConfig(const void * data, int size);
101  int readConfig(void * data, int size);
102  bool writeConfig(const void * data, int size, int timeout);
103  int readConfig(void * data, int size, int timeout);
104 
105  bool writeStream(const void * data, int size);
106  int readStream(void * data, int size);
107 
108  bool ready_;
109  bool heap_dev_;
111  Callback recv_callback_;
112  uint16_t version_major_;
113  uint16_t version_minor_;
114  uint16_t version_build_;
115  uint16_t version_comms_;
116  uint32_t serial_number_;
118  unsigned int num_channels_;
119 
121 };
122 
123 } // namespace dataspeed_can_usb
124 
125 #endif // _DATASPEED_CAN_USB_CAN_USB_H
126 
unsigned int numChannels() const
Definition: CanUsb.h:71
lusb::UsbDevice * dev_
Definition: CanUsb.h:110
unsigned int num_channels_
Definition: CanUsb.h:118
uint32_t serialNumber() const
Definition: CanUsb.h:69
void setRecvCallback(const Callback &callback)
Definition: CanUsb.h:89
uint16_t versionBuild() const
Definition: CanUsb.h:67
boost::function< void(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8])> Callback
Definition: CanUsb.h:88
uint16_t versionMinor() const
Definition: CanUsb.h:66
uint16_t versionMajor() const
Definition: CanUsb.h:65
MacAddr macAddr() const
Definition: CanUsb.h:70
uint16_t versionComms() const
Definition: CanUsb.h:68


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