37 #include <std_msgs/String.h>
48 if (str.length() > 2) {
49 if ((str.at(0) ==
'0') && (str.at(1) ==
'x')) {
52 ss << std::hex << str.substr(2);
66 if (str ==
"normal") {
68 }
else if (str ==
"listen-only") {
75 nh_(nh), nh_priv_(nh_priv), name_(name), total_drops_(0), firmware_(firmware)
86 priv_nh.getParam(
"sync_time", sync_time_);
88 nh_priv.
getParam(
"bitrate", channel.bitrate);
90 nh_priv.
getParam(
"error_topic", error_topic_);
91 nh_priv.
getParam(
"mac_addr", mac_addr_);
97 std::stringstream ss1, ss2;
98 ss1 <<
"bitrate_" << (i + 1);
99 ss2 <<
"mode_" << (i + 1);
100 nh_priv.
getParam(ss1.str(), channels_[i].bitrate);
106 std::stringstream ss1, ss2;
107 ss1 <<
"channel_" << (i + 1) <<
"_mask_" << j;
108 ss2 <<
"channel_" << (i + 1) <<
"_match_" << j;
109 success &=
getParamHex(nh_priv, ss1.str(), (
int&)filter.mask);
110 success &=
getParamHex(nh_priv, ss2.str(), (
int&)filter.match);
112 channels_[i].filters.push_back(filter);
124 CanDriver::~CanDriver()
127 if (dev_->isOpen()) {
135 void CanDriver::recvRos(
const can_msgs::Frame::ConstPtr& msg,
unsigned int channel)
137 dev_->sendMessage(channel, msg->id, msg->is_extended, msg->dlc, msg->data.elems);
140 void CanDriver::recvDevice(
unsigned int channel, uint32_t
id,
bool extended, uint8_t dlc,
const uint8_t data[8])
142 boost::lock_guard<boost::mutex> lock(mutex_);
143 if (channel < pubs_.size()) {
148 msg.is_extended = extended;
149 msg.is_error = (dlc == 0x0F);
151 memcpy(msg.data.elems, data, 8);
152 if (msg.is_error && (channel < pubs_err_.size())) {
153 pubs_err_[channel].publish(msg);
155 pubs_[channel].publish(msg);
161 unsigned int dev_time;
163 if (dev_->getTimeStamp(dev_time)) {
167 int64_t nsec = (t2 - t0).toNSec();
177 void CanDriver::serviceDevice()
179 if (!dev_->isOpen()) {
180 boost::lock_guard<boost::mutex> lock(mutex_);
184 pub_version_.shutdown();
185 if (dev_->open(mac_addr_)) {
187 const ModuleVersion version(dev_->versionMajor(), dev_->versionMinor(), dev_->versionBuild());
188 ROS_INFO(
"%s: version %s", name_.c_str(), dev_->version().c_str());
189 std_msgs::String version_msg;
190 pub_version_ = nh_priv_.advertise<std_msgs::String>(
"version", 1,
true);
191 version_msg.data = dev_->version().c_str();
192 pub_version_.publish(version_msg);
193 ROS_INFO(
"%s: MAC address %s", name_.c_str(), dev_->macAddr().toString().c_str());
194 if (firmware_.valid() && version < firmware_) {
195 ROS_WARN(
"Detected old %s firmware version %u.%u.%u, updating to %u.%u.%u is suggested. Execute `%s` to update.", name_.c_str(),
196 version.major(), version.minor(), version.build(),
197 firmware_.major(), firmware_.minor(), firmware_.build(),
198 "rosrun dataspeed_can_usb fw_update.bash");
202 ROS_INFO(
"%s: Synchronizing time...", name_.c_str());
204 for (
unsigned int i = 0; i < 10; i++) {
205 sampleTimeOffset(offset, delay);
206 ROS_INFO(
"%s: Offset: %f seconds, Delay: %f seconds", name_.c_str(), offset.
toSec(), delay.
toSec());
210 if (!sync_time_ || synced) {
212 for (
unsigned int i = 0; i < dev_->numChannels(); i++) {
213 for (
unsigned int j = 0; j < channels_[i].filters.size(); j++) {
214 const uint32_t mask = channels_[i].filters[j].mask;
215 const uint32_t match = channels_[i].filters[j].match;
216 if (dev_->addFilter(i, mask, match)) {
217 ROS_INFO(
"%s: Ch%u, Mask: 0x%08X, Match: 0x%08X", name_.c_str(), i + 1, mask, match);
219 ROS_WARN(
"%s: Ch%u, Mask: 0x%08X, Match: 0x%08X failed", name_.c_str(), i + 1, mask, match);
223 for (
unsigned int i = 0; i < dev_->numChannels(); i++) {
224 const int bitrate = i < channels_.size() ? channels_[i].bitrate : 0;
225 const uint8_t mode = i < channels_.size() ? channels_[i].mode : 0;
226 if (dev_->setBitrate(i, bitrate, mode)) {
227 ROS_INFO(
"%s: Ch%u %ukbps", name_.c_str(), i + 1, bitrate / 1000);
229 ROS_WARN(
"%s: Ch%u %ukbps failed", name_.c_str(), i + 1, bitrate / 1000);
235 for (
unsigned int i = 0; i < dev_->numChannels(); i++) {
236 if (i < channels_.size() && channels_[i].bitrate) {
237 std::stringstream ns;
238 ns <<
"can_bus_" << (i + 1);
240 if (channels_[i].mode) {
245 pubs_.push_back(node.advertise<can_msgs::Frame>(
"can_rx", 100,
false));
247 pubs_err_.push_back(node.advertise<can_msgs::Frame>(
"can_err", 100,
false));
260 ROS_WARN(
"%s: Failed to set bitrate", name_.c_str());
264 ROS_WARN(
"%s: Failed to sync time", name_.c_str());
268 ROS_WARN(
"%s: Failed to reset", name_.c_str());
271 if (mac_addr_.empty()) {
274 ROS_WARN_THROTTLE(10.0,
"%s: MAC address '%s' not found", name_.c_str(), mac_addr_.c_str());
278 std::vector<uint32_t> rx_drops, tx_drops;
279 std::vector<uint8_t> rx_errors, tx_errors;
280 if (dev_->getStats(rx_drops, tx_drops, rx_errors, tx_errors,
true)) {
281 unsigned int size = std::min(rx_drops.size(), tx_drops.size());
283 for (
unsigned int i = 0; i < size; i++) {
284 total += rx_drops[i];
285 total += tx_drops[i];
287 if (total != total_drops_) {
288 total_drops_ = total;
289 std::stringstream ss;
290 for (
unsigned int i = 0; i < size; i++) {
291 ss <<
"Rx" << (i + 1) <<
": " << rx_drops[i] <<
", ";
292 ss <<
"Tx" << (i + 1) <<
": " << tx_drops[i] <<
", ";
294 ROS_WARN(
"Dropped CAN messages: %s", ss.str().c_str());
307 dev_->flushMessages();