35 #ifndef _DATASPEED_CAN_USB_CAN_DRIVER_H_ 36 #define _DATASPEED_CAN_USB_CAN_DRIVER_H_ 41 #include <can_msgs/Frame.h> 44 #include <boost/thread/mutex.hpp> 45 #include <boost/thread/lock_guard.hpp> 63 const std::string &name = std::string(
"Dataspeed USB CAN Tool"),
70 void recvRos(
const can_msgs::Frame::ConstPtr& msg,
unsigned int channel);
72 void recvDevice(
unsigned int channel, uint32_t
id,
bool extended, uint8_t dlc,
const uint8_t data[8]);
76 return ros::WallTime(dev_stamp / 1000000, (dev_stamp % 1000000) * 1000);
129 #endif // _DATASPEED_CAN_USB_CAN_DRIVER_H_
std::vector< ros::Subscriber > subs_
std::vector< ros::Publisher > pubs_err_
ros::WallTimer timer_flush_
std::vector< ros::Publisher > pubs_
ros::Publisher pub_version_
ros::WallTime stampDev2Ros(unsigned int dev_stamp)
std::vector< Filter > filters
std::vector< Channel > channels_
ros::WallTimer timer_service_