Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef _DATASPEED_CAN_USB_CAN_DRIVER_H_
00036 #define _DATASPEED_CAN_USB_CAN_DRIVER_H_
00037
00038 #include <ros/ros.h>
00039
00040
00041 #include <can_msgs/Frame.h>
00042
00043
00044 #include <boost/thread/mutex.hpp>
00045 #include <boost/thread/lock_guard.hpp>
00046
00047
00048 #include <dataspeed_can_usb/ModuleVersion.h>
00049
00050 namespace lusb
00051 {
00052 class UsbDevice;
00053 }
00054
00055 namespace dataspeed_can_usb
00056 {
00057 class CanUsb;
00058
00059 class CanDriver
00060 {
00061 public:
00062 CanDriver(ros::NodeHandle &nh, ros::NodeHandle &nh_priv, lusb::UsbDevice *dev = NULL,
00063 const std::string &name = std::string("Dataspeed USB CAN Tool"),
00064 const ModuleVersion &firmware = ModuleVersion(10,4,0));
00065 ~CanDriver();
00066
00067 private:
00068 void timerServiceCallback(const ros::WallTimerEvent& event);
00069 void timerFlushCallback(const ros::WallTimerEvent& event);
00070 void recvRos(const can_msgs::Frame::ConstPtr& msg, unsigned int channel);
00071
00072 void recvDevice(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8]);
00073 void serviceDevice();
00074 bool sampleTimeOffset(ros::WallDuration &offset, ros::WallDuration &delay);
00075 inline ros::WallTime stampDev2Ros(unsigned int dev_stamp) {
00076 return ros::WallTime(dev_stamp / 1000000, (dev_stamp % 1000000) * 1000);
00077 }
00078
00079
00080 ros::NodeHandle nh_;
00081 ros::NodeHandle nh_priv_;
00082
00083
00084 bool sync_time_;
00085 bool error_topic_;
00086 std::string mac_addr_;
00087 struct Filter {
00088 uint32_t mask;
00089 uint32_t match;
00090 };
00091 struct Channel {
00092 Channel() : bitrate(0), mode(0) {}
00093 int bitrate;
00094 uint8_t mode;
00095 std::vector<Filter> filters;
00096 };
00097 std::vector<Channel> channels_;
00098
00099
00100 ros::WallTimer timer_service_;
00101 ros::WallTimer timer_flush_;
00102
00103
00104 CanUsb *dev_;
00105
00106
00107 std::vector<ros::Subscriber> subs_;
00108
00109
00110 ros::Publisher pub_version_;
00111 std::vector<ros::Publisher> pubs_;
00112 std::vector<ros::Publisher> pubs_err_;
00113
00114
00115 boost::mutex mutex_;
00116
00117
00118 std::string name_;
00119
00120
00121 uint32_t total_drops_;
00122
00123
00124 ModuleVersion firmware_;
00125 };
00126
00127 }
00128
00129 #endif // _DATASPEED_CAN_USB_CAN_DRIVER_H_
00130