DbcBuilder.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018 New Eagle
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 New Eagle 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 #ifndef _NEW_EAGLE_DBCBUILDER_H
00036 #define _NEW_EAGLE_DBCBUILDER_H
00037 
00038 #include <ros/ros.h>
00039 
00040 #include <string>
00041 
00042 #include <dbc/Dbc.h>
00043 
00044 #include "LineParser.h"
00045 
00046 namespace NewEagle
00047 {
00048   struct DbcSignalValueType
00049   {
00050     uint32_t Id;
00051     std::string SignalName;
00052     NewEagle::DataType Type;
00053   };
00054 
00055   struct DbcAttribute
00056   {
00057     std::string AttributeName;
00058     uint32_t Id;
00059     std::string ObjectType;
00060     std::string SignalName;
00061     std::string Value;
00062   };
00063 
00064   class DbcBuilder
00065   {
00066     public:
00067       DbcBuilder();
00068       ~DbcBuilder();
00069 
00070       NewEagle::Dbc NewDbc(const std::string &dbcFile);
00071 
00072     private:
00073       std::string MessageToken;
00074       std::string SignalToken;
00075       std::string CommentToken;
00076       std::string EnumValueToken;
00077       std::string AttributeToken;
00078       std::string SignalValueTypeToken;
00079   };
00080 
00081 
00082       static NewEagle::DbcSignalValueType ReadSignalValueType(NewEagle::LineParser parser)
00083       {
00084         NewEagle::DbcSignalValueType signalValueType;
00085 
00086         signalValueType.Id = parser.ReadUInt("id");
00087         signalValueType.SignalName = parser.ReadCIdentifier();
00088         parser.SeekSeparator(':');
00089         signalValueType.Type = parser.ReadUInt("DataType") == 1 ? NewEagle::FLOAT : NewEagle::DOUBLE;
00090 
00091         return signalValueType;
00092       }
00093 
00094       static NewEagle::DbcAttribute ReadAttribute(NewEagle::LineParser parser)
00095       {
00096         NewEagle::DbcAttribute attribute;
00097 
00098         try
00099         {
00100           attribute.AttributeName = parser.ReadQuotedString();
00101           if (attribute.AttributeName == "GenSigStartValue")
00102           {
00103               attribute.ObjectType = parser.ReadCIdentifier();
00104               attribute.Id = parser.ReadUInt("id");
00105               if (attribute.ObjectType == "SG_")
00106               {
00107                 attribute.SignalName = parser.ReadCIdentifier();
00108 
00109                 std::ostringstream sstream;
00110                 sstream << parser.ReadDouble();
00111                 attribute.Value = sstream.str();
00112               }
00113           }
00114         }
00115         catch(std::exception& ex)
00116         {
00117           throw;
00118         }
00119 
00120         return attribute;
00121       }
00122 
00123       static NewEagle::DbcMessageComment ReadMessageComment(NewEagle::LineParser parser)
00124       {
00125         NewEagle::DbcMessageComment comment;
00126         comment.Id = parser.ReadUInt("id");
00127         comment.Comment = parser.ReadQuotedString();
00128 
00129         return comment;
00130       }
00131 
00132       static NewEagle::DbcSignalComment ReadSignalComment(NewEagle::LineParser parser)
00133       {
00134         NewEagle::DbcSignalComment comment;
00135         comment.Id = parser.ReadUInt("id");
00136         comment.SignalName = parser.ReadCIdentifier();
00137         comment.Comment = parser.ReadQuotedString();
00138 
00139         return comment;
00140       }
00141 
00142       static NewEagle::DbcMessage ReadMessage(NewEagle::LineParser parser)
00143       {
00144         uint32_t canId = parser.ReadUInt("message id");
00145         IdType idType = ((canId & 0x80000000u) > 0) ? NewEagle::EXT : NewEagle::STD;
00146         std::string name(parser.ReadCIdentifier("message name"));
00147         parser.SeekSeparator(':');
00148         uint8_t dlc = parser.ReadUInt("size");
00149         std::string sendingNode(parser.ReadCIdentifier("transmitter"));
00150         uint32_t id = (uint32_t)(canId & 0x3FFFFFFFu);
00151 
00152         NewEagle::DbcMessage msg(dlc, id, idType, name, canId);
00153         return msg;
00154       }
00155 
00156       static NewEagle::DbcSignal ReadSignal(NewEagle::LineParser parser)
00157       {
00158         std::string name = parser.ReadCIdentifier();
00159         char mux = parser.ReadNextChar("mux");
00160         NewEagle::MultiplexerMode multiplexMode = NewEagle::NONE;
00161         int32_t muxSwitch = 0;
00162 
00163         switch (mux) {
00164           case ':':
00165             multiplexMode = NewEagle::NONE;
00166             break;
00167           case 'M':
00168             multiplexMode = NewEagle::MUX_SWITCH;
00169             parser.SeekSeparator(':');
00170             break;
00171           case 'm':
00172             multiplexMode = NewEagle::MUX_SIGNAL;
00173             muxSwitch = parser.ReadInt();
00174             parser.SeekSeparator(':');
00175             break;
00176           default:
00177             throw std::runtime_error("Synxax Error: Expected \':\' " + parser.GetPosition());
00178         }
00179 
00180         int32_t startBit = parser.ReadUInt("start bit");
00181 
00182         parser.SeekSeparator('|');
00183 
00184         uint8_t length = (uint8_t)parser.ReadUInt("size");
00185         parser.SeekSeparator('@');
00186 
00187         char byteOrder = parser.ReadNextChar("byte order");
00188 
00189         NewEagle::ByteOrder endianness;
00190 
00191         switch (byteOrder) {
00192           case '1':
00193             endianness = NewEagle::LITTLE_END;
00194             break;
00195           case '0':
00196             endianness = NewEagle::BIG_END;
00197             break;
00198           default:
00199             throw std::runtime_error("Synxax Error: Byte Order - Expected 0 or 1, got " + byteOrder);
00200         }
00201 
00202         char valType = parser.ReadNextChar("value type");
00203         NewEagle::SignType sign;
00204 
00205         switch (valType) {
00206           case '+':
00207             sign = NewEagle::UNSIGNED;
00208             break;
00209           case '-':
00210             sign = NewEagle::SIGNED;
00211             break;
00212           default:
00213             throw std::runtime_error("Synxax Error: Value Type - Expected + or -, got " + valType);
00214         }
00215 
00216         // Set the default data type: INT.
00217         //  Might be changed what parsing SIG_VALTYPE_
00218         NewEagle::DataType type = NewEagle::INT;
00219 
00220 
00221         parser.SeekSeparator('(');
00222         double gain = parser.ReadDouble("factor");
00223         parser.SeekSeparator(',');
00224         double offset = parser.ReadDouble("offset");
00225         parser.SeekSeparator(')');
00226 
00227         parser.SeekSeparator('[');
00228         double minimum = parser.ReadDouble("minimum");
00229         parser.SeekSeparator('|');
00230         double maximum = parser.ReadDouble("maximum");
00231         parser.SeekSeparator(']');
00232 
00233         // Need to include Min, Max, DataType, MuxSwitch, Unit, Receiver
00234         // Find a way to include the DLC...
00235         NewEagle::DbcSignal* signal;
00236 
00237         if (NewEagle::MUX_SIGNAL == multiplexMode) {
00238           //NewEagle::DbcSignal signal(8, gain, offset, startBit, endianness, length, sign, name, multiplexMode, muxSwitch);
00239           signal = new NewEagle::DbcSignal(8, gain, offset, startBit, endianness, length, sign, name, multiplexMode, muxSwitch);
00240         }
00241         else {
00242           //NewEagle::DbcSignal signal(8, gain, offset, startBit, endianness, length, sign, name, multiplexMode);
00243           signal = new NewEagle::DbcSignal(8, gain, offset, startBit, endianness, length, sign, name, multiplexMode);
00244         }
00245 
00246         signal->SetDataType(type);
00247         return NewEagle::DbcSignal(*signal);
00248       }
00249 }
00250 
00251 #endif // _NEW_EAGLE_DBCBUILDER_H


dbc
Author(s): Ryan Borchert
autogenerated on Mon Jun 24 2019 19:18:30