DbcSignal.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 "DbcSignal.hpp"
00036 
00037 #include <vector>
00038 #include <istream>
00039 #include <sstream>
00040 #include <limits>
00041 #include <iterator>
00042 #include <algorithm>
00043 
00044 std::string& trim(std::string& str, const std::string& toTrim = " ") {
00045   std::string::size_type pos = str.find_last_not_of(toTrim);
00046   if (pos == std::string::npos) {
00047     str.clear();
00048   } else {
00049     str.erase(pos + 1);
00050     str.erase(0, str.find_first_not_of(toTrim));
00051   }
00052   return str;
00053 }
00054 
00055 std::vector<std::string>& split(const std::string &s, char delim, std::vector<std::string> &elems) {
00056   std::stringstream ss(s);
00057   std::string item;
00058   while (std::getline(ss, item, delim)) {
00059     elems.push_back(item);
00060   }
00061   return elems;
00062 }
00063 
00064 std::vector<std::string> split(const std::string &s, char delim) {
00065   std::vector<std::string> elems;
00066   split(s, delim, elems);
00067   return elems;
00068 }
00069 
00070 std::istream& operator>>(std::istream& in, Signal& sig) {
00071   std::string line;
00072   std::getline(in, line);
00073   if (!line.empty() && *line.rbegin() == '\r') {
00074     line.erase(line.length() - 1, 1);
00075   }
00076   if (line.empty()) {
00077     in.setstate(std::ios_base::failbit);
00078     return in;
00079   }
00080 
00081   // Check if we are actually reading a Signal otherwise fail the stream
00082   std::istringstream sstream(line);
00083   std::string preamble;
00084   sstream >> preamble;
00085   if (preamble != "SG_") {
00086     in.setstate(std::ios_base::failbit);
00087     return in;
00088   }
00089 
00090   // Parse the Signal Name
00091   sstream >> sig.name;
00092 
00093   std::string multi;
00094   sstream >> multi;
00095 
00096   // This case happens if there is no Multiplexor present
00097   if (multi == ":") {
00098     sig.multiplexor = NONE;
00099   } else {
00100     // Case with multiplexor
00101     if (multi == "M") {
00102       sig.multiplexor = MULTIPLEXOR;
00103     } else {
00104       // The multiplexor looks like that 'm12' so we ignore the m and parse it as integer
00105       std::istringstream multstream(multi);
00106       multstream.ignore(1);
00107       unsigned short multiNum;
00108       multstream >> multiNum;
00109       sig.multiplexor = MULTIPLEXED;
00110       sig.multiplexNum = multiNum;
00111     }
00112     //ignore the next thing which is a ':'
00113     sstream >> multi;
00114   }
00115 
00116   sstream >> sig.startBit;
00117   sstream.ignore(1);
00118   sstream >> sig.length;
00119   sstream.ignore(1);
00120 
00121   int order;
00122   sstream >> order;
00123   if (order == 0) {
00124     sig.order = MOTOROLA;
00125   } else {
00126     sig.order = INTEL;
00127   }
00128 
00129   char sign;
00130   sstream >> sign;
00131   if (sign == '+') {
00132     sig.sign = UNSIGNED;
00133   } else {
00134     sig.sign = SIGNED;
00135   }
00136 
00137   // Factor and offset
00138   sstream.ignore(std::numeric_limits<std::streamsize>::max(), '(');
00139   sstream >> sig.factor;
00140   sstream.ignore(1);
00141   sstream >> sig.offset;
00142   sstream.ignore(1);
00143 
00144   // Min and max
00145   sstream.ignore(std::numeric_limits<std::streamsize>::max(), '[');
00146   sstream >> sig.minimum;
00147   sstream.ignore(1);
00148   sstream >> sig.maximum;
00149   sstream.ignore(1);
00150 
00151   // Unit
00152   std::string unit;
00153   sstream >> unit;
00154   sig.unit = trim(unit, "\"");
00155 
00156   // Receivers
00157   std::string to;
00158   sstream >> to;
00159   std::vector<std::string> toStrings = split(to, ',');
00160   for (size_t i = 0; i < toStrings.size(); i++) {
00161     sig.to.insert(sig.to.end(), toStrings[i]);
00162   }
00163 
00164   return in;
00165 }
00166 


dataspeed_can_tools
Author(s): Micho Radovnikovich
autogenerated on Thu Jun 6 2019 21:16:41