CanUsb.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015-2018, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #ifndef _DATASPEED_CAN_USB_CAN_USB_H
00036 #define _DATASPEED_CAN_USB_CAN_USB_H
00037 
00038 #include <stdint.h>
00039 #include <vector>
00040 #include <boost/bind.hpp>
00041 #include <boost/function.hpp>
00042 #include <dataspeed_can_usb/MacAddr.h>
00043 
00044 namespace lusb
00045 {
00046 class UsbDevice;
00047 }
00048 
00049 class TxQueue;
00050 
00051 namespace dataspeed_can_usb
00052 {
00053 
00054 class CanUsb
00055 {
00056 public:
00057   static const int USB_DEFAULT_TIMEOUT = 10;
00058   static const unsigned int MAX_CHANNELS = 4;
00059   static const unsigned int MAX_FILTERS = 32;
00060 
00061   CanUsb(lusb::UsbDevice *dev = NULL);
00062   ~CanUsb();
00063 
00064   std::string version() const;
00065   uint16_t versionMajor() const { return version_major_; }
00066   uint16_t versionMinor() const { return version_minor_; }
00067   uint16_t versionBuild() const { return version_build_; }
00068   uint16_t versionComms() const { return version_comms_; }
00069   uint32_t serialNumber() const { return serial_number_; }
00070   MacAddr macAddr() const { return mac_addr_; }
00071   unsigned int numChannels() const { return num_channels_; }
00072 
00073   bool open(const std::string &mac = std::string());
00074   bool isOpen();
00075   void closeDevice();
00076 
00077   bool reboot();
00078   bool reset();
00079   bool setBitrate(unsigned int channel, uint32_t bitrate, uint8_t mode = 0);
00080   bool addFilter(unsigned int channel, uint32_t mask, uint32_t match);
00081   bool getStats(std::vector<uint32_t> &rx_drops, std::vector<uint32_t> &tx_drops,
00082                 std::vector<uint8_t> &rx_errors, std::vector<uint8_t> &tx_errors, bool clear = false);
00083   bool getTimeStamp(uint32_t &timestamp);
00084 
00085   void sendMessage(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8], bool flush = true);
00086   void flushMessages();
00087 
00088   typedef boost::function<void(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8])> Callback;
00089   void setRecvCallback(const Callback &callback) {
00090     recv_callback_ = callback;
00091   }
00092 
00093 private:
00094   bool readVersion();
00095   bool getNumChannels();
00096   bool configure(const std::string &mac = std::string());
00097 
00098   void recvStream(const void *data, int size);
00099 
00100   bool writeConfig(const void * data, int size);
00101   int readConfig(void * data, int size);
00102   bool writeConfig(const void * data, int size, int timeout);
00103   int readConfig(void * data, int size, int timeout);
00104 
00105   bool writeStream(const void * data, int size);
00106   int readStream(void * data, int size);
00107 
00108   bool ready_;
00109   bool heap_dev_;
00110   lusb::UsbDevice *dev_;
00111   Callback recv_callback_;
00112   uint16_t version_major_;
00113   uint16_t version_minor_;
00114   uint16_t version_build_;
00115   uint16_t version_comms_;
00116   uint32_t serial_number_;
00117   MacAddr mac_addr_;
00118   unsigned int num_channels_;
00119 
00120   TxQueue* queue_;
00121 };
00122 
00123 } // namespace dataspeed_can_usb
00124 
00125 #endif // _DATASPEED_CAN_USB_CAN_USB_H
00126 


dataspeed_can_usb
Author(s): Kevin Hallenbeck
autogenerated on Thu Jun 6 2019 21:16:43