CanDriver.cpp
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 #include <dataspeed_can_usb/CanDriver.h>
00036 #include <dataspeed_can_usb/CanUsb.h>
00037 #include <std_msgs/String.h>
00038 
00039 namespace dataspeed_can_usb
00040 {
00041 
00042 static bool getParamHex(const ros::NodeHandle &nh, const std::string& key, int& i) {
00043   if (nh.getParam(key, i)) {
00044     return true;
00045   } else {
00046     std::string str;
00047     if (nh.getParam(key, str)) {
00048       if (str.length() > 2) {
00049         if ((str.at(0) == '0') && (str.at(1) == 'x')) {
00050           unsigned int u;
00051           std::stringstream ss;
00052           ss << std::hex << str.substr(2);
00053           ss >> u;
00054           if (!ss.fail()) {
00055             i = u;
00056             return true;
00057           }
00058         }
00059       }
00060     }
00061   }
00062   return false;
00063 }
00064 
00065 static uint8_t getModeFromString(const std::string &str) {
00066   if (str == "normal") {
00067     return 0;
00068   } else if (str == "listen-only") {
00069     return 1;
00070   }
00071   return 0; // Default to "normal"
00072 }
00073 
00074 CanDriver::CanDriver(ros::NodeHandle &nh, ros::NodeHandle &nh_priv, lusb::UsbDevice *dev, const std::string &name, const ModuleVersion &firmware) :
00075     nh_(nh), nh_priv_(nh_priv), name_(name), total_drops_(0), firmware_(firmware)
00076 {
00077   dev_ = new CanUsb(dev);
00078   dev_->setRecvCallback(boost::bind(&CanDriver::recvDevice, this, _1, _2, _3, _4, _5));
00079 
00080   // Get Parameters
00081   sync_time_ = false;
00082   error_topic_ = true;
00083   std::string mode;
00084   Channel channel;
00085 #if 0
00086   priv_nh.getParam("sync_time", sync_time_);
00087 #endif
00088   nh_priv.getParam("bitrate", channel.bitrate);
00089   nh_priv.getParam("mode", mode);
00090   nh_priv.getParam("error_topic", error_topic_);
00091   nh_priv.getParam("mac_addr", mac_addr_);
00092 
00093   channel.mode = getModeFromString(mode);
00094   channels_.resize(CanUsb::MAX_CHANNELS, channel);
00095   for (unsigned int i = 0; i < CanUsb::MAX_CHANNELS; i++) {
00096     std::string mode;
00097     std::stringstream ss1, ss2;
00098     ss1 << "bitrate_" << (i + 1);
00099     ss2 << "mode_" << (i + 1);
00100     nh_priv.getParam(ss1.str(), channels_[i].bitrate);
00101     nh_priv.getParam(ss2.str(), mode);
00102     channels_[i].mode = getModeFromString(mode);
00103     for (unsigned int j = 0; j < CanUsb::MAX_FILTERS; j++) {
00104       bool success = true;
00105       Filter filter;
00106       std::stringstream ss1, ss2;
00107       ss1 << "channel_" << (i + 1) << "_mask_" << j;
00108       ss2 << "channel_" << (i + 1) << "_match_" << j;
00109       success &= getParamHex(nh_priv, ss1.str(), (int&)filter.mask);
00110       success &= getParamHex(nh_priv, ss2.str(), (int&)filter.match);
00111       if (success) {
00112         channels_[i].filters.push_back(filter);
00113       }
00114     }
00115   }
00116 
00117   serviceDevice();
00118 
00119   // Setup Timers
00120   timer_service_ = nh.createWallTimer(ros::WallDuration(0.1), &CanDriver::timerServiceCallback, this);
00121   timer_flush_ = nh.createWallTimer(ros::WallDuration(0.001), &CanDriver::timerFlushCallback, this);
00122 }
00123 
00124 CanDriver::~CanDriver()
00125 {
00126   if (dev_) {
00127     if (dev_->isOpen()) {
00128       dev_->reset();
00129     }
00130     delete dev_;
00131     dev_ = NULL;
00132   }
00133 }
00134 
00135 void CanDriver::recvRos(const can_msgs::Frame::ConstPtr& msg, unsigned int channel)
00136 {
00137   dev_->sendMessage(channel, msg->id, msg->is_extended, msg->dlc, msg->data.elems);
00138 }
00139 
00140 void CanDriver::recvDevice(unsigned int channel, uint32_t id, bool extended, uint8_t dlc, const uint8_t data[8])
00141 {
00142   boost::lock_guard<boost::mutex> lock(mutex_);
00143   if (channel < pubs_.size()) {
00144     can_msgs::Frame msg;
00145     msg.header.stamp = ros::Time::now();
00146     msg.id = id;
00147     msg.is_rtr = false;
00148     msg.is_extended = extended;
00149     msg.is_error = (dlc == 0x0F);
00150     msg.dlc = dlc;
00151     memcpy(msg.data.elems, data, 8);
00152     if (msg.is_error && (channel < pubs_err_.size())) {
00153       pubs_err_[channel].publish(msg);
00154     } else {
00155       pubs_[channel].publish(msg);
00156     }
00157   }
00158 }
00159 
00160 bool CanDriver::sampleTimeOffset(ros::WallDuration &offset, ros::WallDuration &delay) {
00161   unsigned int dev_time;
00162   ros::WallTime t0 = ros::WallTime::now();
00163   if (dev_->getTimeStamp(dev_time)) {
00164     ros::WallTime t2 = ros::WallTime::now();
00165     ros::WallTime t1 = stampDev2Ros(dev_time);
00166     delay = t2 - t0;
00167     int64_t nsec = (t2 - t0).toNSec();
00168     ros::WallDuration delta;
00169     delta.fromNSec(nsec / 2);
00170     ros::WallTime asdf = t0 + delta;
00171     offset = asdf - t1;
00172     return true;
00173   }
00174   return false;
00175 }
00176 
00177 void CanDriver::serviceDevice()
00178 {
00179   if (!dev_->isOpen()) {
00180     boost::lock_guard<boost::mutex> lock(mutex_);
00181     pubs_err_.clear();
00182     pubs_.clear();
00183     subs_.clear();
00184     pub_version_.shutdown();
00185     if (dev_->open(mac_addr_)) {
00186       if (dev_->reset()) {
00187         const ModuleVersion version(dev_->versionMajor(), dev_->versionMinor(), dev_->versionBuild());
00188         ROS_INFO("%s: version %s", name_.c_str(), dev_->version().c_str());
00189         std_msgs::String version_msg;
00190         pub_version_ = nh_priv_.advertise<std_msgs::String>("version", 1, true);
00191         version_msg.data = dev_->version().c_str();
00192         pub_version_.publish(version_msg);
00193         ROS_INFO("%s: MAC address %s", name_.c_str(), dev_->macAddr().toString().c_str());
00194         if (firmware_.valid() && version < firmware_) {
00195           ROS_WARN("Detected old %s firmware version %u.%u.%u, updating to %u.%u.%u is suggested. Execute `%s` to update.", name_.c_str(),
00196                    version.major(), version.minor(), version.build(),
00197                    firmware_.major(), firmware_.minor(), firmware_.build(),
00198                    "rosrun dataspeed_can_usb fw_update.bash");
00199         }
00200         bool synced = false;
00201         if (sync_time_) {
00202           ROS_INFO("%s: Synchronizing time...", name_.c_str());
00203           ros::WallDuration offset, delay;
00204           for (unsigned int i = 0; i < 10; i++) {
00205             sampleTimeOffset(offset, delay);
00206             ROS_INFO("%s: Offset: %f seconds, Delay: %f seconds", name_.c_str(), offset.toSec(), delay.toSec());
00207           }
00208           synced = true;
00209         }
00210         if (!sync_time_ || synced) {
00211           bool success = true;
00212           for (unsigned int i = 0; i < dev_->numChannels(); i++) {
00213             for (unsigned int j = 0; j < channels_[i].filters.size(); j++) {
00214               const uint32_t mask = channels_[i].filters[j].mask;
00215               const uint32_t match = channels_[i].filters[j].match;
00216               if (dev_->addFilter(i, mask, match)) {
00217                 ROS_INFO("%s: Ch%u, Mask: 0x%08X, Match: 0x%08X", name_.c_str(), i + 1, mask, match);
00218               } else {
00219                 ROS_WARN("%s: Ch%u, Mask: 0x%08X, Match: 0x%08X failed", name_.c_str(), i + 1, mask, match);
00220               }
00221             }
00222           }
00223           for (unsigned int i = 0; i < dev_->numChannels(); i++) {
00224             const int bitrate = i < channels_.size() ? channels_[i].bitrate : 0;
00225             const uint8_t mode = i < channels_.size() ? channels_[i].mode : 0;
00226             if (dev_->setBitrate(i, bitrate, mode)) {
00227               ROS_INFO("%s: Ch%u %ukbps", name_.c_str(), i + 1, bitrate / 1000);
00228             } else {
00229               ROS_WARN("%s: Ch%u %ukbps failed", name_.c_str(), i + 1, bitrate / 1000);
00230               success = false;
00231             }
00232           }
00233           if (success) {
00234             // Setup Publishers and Subscribers
00235             for (unsigned int i = 0; i < dev_->numChannels(); i++) {
00236               if (i < channels_.size() && channels_[i].bitrate) {
00237                 std::stringstream ns;
00238                 ns << "can_bus_" << (i + 1);
00239                 ros::NodeHandle node(nh_, ns.str());
00240                 if (channels_[i].mode) {
00241                   subs_.push_back(ros::Subscriber()); // Listen-only mode cannot transmit
00242                 } else {
00243                   subs_.push_back(node.subscribe<can_msgs::Frame>("can_tx", 100, boost::bind(&CanDriver::recvRos, this, _1, i), ros::VoidConstPtr(), ros::TransportHints().tcpNoDelay()));
00244                 }
00245                 pubs_.push_back(node.advertise<can_msgs::Frame>("can_rx", 100, false));
00246                 if (error_topic_) {
00247                   pubs_err_.push_back(node.advertise<can_msgs::Frame>("can_err", 100, false));
00248                 }
00249               } else {
00250                 subs_.push_back(ros::Subscriber());
00251                 pubs_.push_back(ros::Publisher());
00252                 if (error_topic_) {
00253                   pubs_err_.push_back(ros::Publisher());
00254                 }
00255               }
00256             }
00257           } else {
00258             dev_->reset();
00259             dev_->closeDevice();
00260             ROS_WARN("%s: Failed to set bitrate", name_.c_str());
00261           }
00262         } else {
00263           dev_->closeDevice();
00264           ROS_WARN("%s: Failed to sync time", name_.c_str());
00265         }
00266       } else {
00267         dev_->closeDevice();
00268         ROS_WARN("%s: Failed to reset", name_.c_str());
00269       }
00270     } else {
00271       if (mac_addr_.empty()) {
00272         ROS_WARN_THROTTLE(10.0, "%s: Not found", name_.c_str());
00273       } else {
00274         ROS_WARN_THROTTLE(10.0, "%s: MAC address '%s' not found", name_.c_str(), mac_addr_.c_str());
00275       }
00276     }
00277   } else {
00278     std::vector<uint32_t> rx_drops, tx_drops;
00279     std::vector<uint8_t> rx_errors, tx_errors;
00280     if (dev_->getStats(rx_drops, tx_drops, rx_errors, tx_errors, true)) {
00281       unsigned int size = std::min(rx_drops.size(), tx_drops.size());
00282       uint32_t total = 0;
00283       for (unsigned int i = 0; i < size; i++) {
00284         total += rx_drops[i];
00285         total += tx_drops[i];
00286       }
00287       if (total != total_drops_) {
00288         total_drops_ = total;
00289         std::stringstream ss;
00290         for (unsigned int i = 0; i < size; i++) {
00291           ss << "Rx" << (i + 1) << ": " << rx_drops[i] << ", ";
00292           ss << "Tx" << (i + 1) << ": " << tx_drops[i] << ", ";
00293         }
00294         ROS_WARN("Dropped CAN messages: %s", ss.str().c_str());
00295       }
00296     }
00297   }
00298 }
00299 
00300 void CanDriver::timerServiceCallback(const ros::WallTimerEvent&)
00301 {
00302   serviceDevice();
00303 }
00304 
00305 void CanDriver::timerFlushCallback(const ros::WallTimerEvent&)
00306 {
00307   dev_->flushMessages();
00308 }
00309 
00310 } // namespace dataspeed_can_usb
00311 


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