CanDriver.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_DRIVER_H_
36 #define _DATASPEED_CAN_USB_CAN_DRIVER_H_
37 
38 #include <ros/ros.h>
39 
40 // ROS messages
41 #include <can_msgs/Frame.h>
42 
43 // Mutex
44 #include <boost/thread/mutex.hpp>
45 #include <boost/thread/lock_guard.hpp>
46 
47 // Module Version class
49 
50 namespace lusb
51 {
52 class UsbDevice;
53 }
54 
56 {
57 class CanUsb;
58 
59 class CanDriver
60 {
61 public:
62  CanDriver(ros::NodeHandle &nh, ros::NodeHandle &nh_priv, lusb::UsbDevice *dev = NULL,
63  const std::string &name = std::string("Dataspeed USB CAN Tool"),
64  const ModuleVersion &firmware = ModuleVersion(10,4,0));
65  ~CanDriver();
66 
67 private:
68  void timerServiceCallback(const ros::WallTimerEvent& event);
69  void timerFlushCallback(const ros::WallTimerEvent& event);
70  void recvRos(const can_msgs::Frame::ConstPtr& msg, unsigned int channel);
71 
72  void recvDevice(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8]);
73  void serviceDevice();
75  inline ros::WallTime stampDev2Ros(unsigned int dev_stamp) {
76  return ros::WallTime(dev_stamp / 1000000, (dev_stamp % 1000000) * 1000);
77  }
78 
79  // NodeHandle
82 
83  // Parameters
84  bool sync_time_;
86  std::string mac_addr_;
87  struct Filter {
88  uint32_t mask;
89  uint32_t match;
90  };
91  struct Channel {
92  Channel() : bitrate(0), mode(0) {}
93  int bitrate;
94  uint8_t mode;
95  std::vector<Filter> filters;
96  };
97  std::vector<Channel> channels_;
98 
99  // Timers
102 
103  // USB Device
105 
106  // Subscribed topics
107  std::vector<ros::Subscriber> subs_;
108 
109  // Published topics
111  std::vector<ros::Publisher> pubs_;
112  std::vector<ros::Publisher> pubs_err_;
113 
114  // Mutex for vector of publishers
115  boost::mutex mutex_;
116 
117  // Name prefix for print statements
118  std::string name_;
119 
120  // Number of total drops for status warnings
121  uint32_t total_drops_;
122 
123  // Latest firmware version
125 };
126 
127 } // namespace dataspeed_can_usb
128 
129 #endif // _DATASPEED_CAN_USB_CAN_DRIVER_H_
130 
dataspeed_can_usb::CanDriver::timerServiceCallback
void timerServiceCallback(const ros::WallTimerEvent &event)
Definition: CanDriver.cpp:332
dataspeed_can_usb::CanDriver::Filter::match
uint32_t match
Definition: CanDriver.h:89
dataspeed_can_usb::CanDriver::Filter
Definition: CanDriver.h:87
ros::Publisher
dataspeed_can_usb::CanDriver::~CanDriver
~CanDriver()
Definition: CanDriver.cpp:156
dataspeed_can_usb::CanDriver::sampleTimeOffset
bool sampleTimeOffset(ros::WallDuration &offset, ros::WallDuration &delay)
Definition: CanDriver.cpp:192
dataspeed_can_usb::CanDriver::name_
std::string name_
Definition: CanDriver.h:118
ros.h
dataspeed_can_usb::CanDriver::serviceDevice
void serviceDevice()
Definition: CanDriver.cpp:209
dataspeed_can_usb::CanDriver::recvRos
void recvRos(const can_msgs::Frame::ConstPtr &msg, unsigned int channel)
Definition: CanDriver.cpp:167
dataspeed_can_usb::CanDriver::error_topic_
bool error_topic_
Definition: CanDriver.h:85
ros::WallTimer
dataspeed_can_usb::CanDriver::Channel
Definition: CanDriver.h:91
dataspeed_can_usb::CanDriver::recvDevice
void recvDevice(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8])
Definition: CanDriver.cpp:172
dataspeed_can_usb::CanDriver::dev_
CanUsb * dev_
Definition: CanDriver.h:104
dataspeed_can_usb::CanDriver::nh_priv_
ros::NodeHandle nh_priv_
Definition: CanDriver.h:81
dataspeed_can_usb::CanDriver::Channel::mode
uint8_t mode
Definition: CanDriver.h:94
dataspeed_can_usb::CanDriver::pub_version_
ros::Publisher pub_version_
Definition: CanDriver.h:110
dataspeed_can_usb::CanDriver::mutex_
boost::mutex mutex_
Definition: CanDriver.h:115
dataspeed_can_usb::CanDriver::nh_
ros::NodeHandle nh_
Definition: CanDriver.h:80
dataspeed_can_usb::CanDriver::Channel::bitrate
int bitrate
Definition: CanDriver.h:93
dataspeed_can_usb::CanDriver::mac_addr_
std::string mac_addr_
Definition: CanDriver.h:86
dataspeed_can_usb::CanDriver::Filter::mask
uint32_t mask
Definition: CanDriver.h:88
dataspeed_can_usb::CanDriver::subs_
std::vector< ros::Subscriber > subs_
Definition: CanDriver.h:107
dataspeed_can_usb::CanDriver::CanDriver
CanDriver(ros::NodeHandle &nh, ros::NodeHandle &nh_priv, lusb::UsbDevice *dev=NULL, const std::string &name=std::string("Dataspeed USB CAN Tool"), const ModuleVersion &firmware=ModuleVersion(10, 4, 0))
Definition: CanDriver.cpp:106
lusb
dataspeed_can_usb::CanDriver::stampDev2Ros
ros::WallTime stampDev2Ros(unsigned int dev_stamp)
Definition: CanDriver.h:75
ros::WallTime
dataspeed_can_usb::CanDriver::sync_time_
bool sync_time_
Definition: CanDriver.h:84
dataspeed_can_usb::CanDriver::pubs_
std::vector< ros::Publisher > pubs_
Definition: CanDriver.h:111
dataspeed_can_usb::CanDriver::Channel::filters
std::vector< Filter > filters
Definition: CanDriver.h:95
dataspeed_can_usb::CanDriver::Channel::Channel
Channel()
Definition: CanDriver.h:92
dataspeed_can_usb::CanDriver::channels_
std::vector< Channel > channels_
Definition: CanDriver.h:97
dataspeed_can_usb::CanDriver::timer_service_
ros::WallTimer timer_service_
Definition: CanDriver.h:100
dataspeed_can_usb::CanDriver
Definition: CanDriver.h:59
ros::WallTimerEvent
dataspeed_can_usb::CanDriver::pubs_err_
std::vector< ros::Publisher > pubs_err_
Definition: CanDriver.h:112
dataspeed_can_usb::CanDriver::timerFlushCallback
void timerFlushCallback(const ros::WallTimerEvent &event)
Definition: CanDriver.cpp:337
lusb::UsbDevice
ModuleVersion.h
dataspeed_can_usb
Definition: CanDriver.h:55
dataspeed_can_usb::CanDriver::firmware_
ModuleVersion firmware_
Definition: CanDriver.h:124
ros::WallDuration
dataspeed_can_usb::CanUsb
Definition: CanUsb.h:54
dataspeed_can_usb::CanDriver::timer_flush_
ros::WallTimer timer_flush_
Definition: CanDriver.h:101
dataspeed_can_usb::CanDriver::total_drops_
uint32_t total_drops_
Definition: CanDriver.h:121
ros::NodeHandle
dataspeed_can_usb::ModuleVersion
Definition: ModuleVersion.h:83


dataspeed_can_usb
Author(s): Kevin Hallenbeck
autogenerated on Sat Feb 4 2023 03:39:26