DbcBuilder.cpp
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 #include <dbc/DbcBuilder.h>
00036 #include <dbc/DbcMessage.h>
00037 #include <dbc/DbcSignal.h>
00038 
00039 namespace NewEagle
00040 {
00041   DbcBuilder::DbcBuilder()
00042   {
00043     MessageToken = std::string("BO_");
00044     SignalToken = std::string("SG_");
00045     CommentToken = std::string("CM_");
00046     EnumValueToken = std::string("VAL_");
00047     AttributeToken = std::string("BA_");
00048     SignalValueTypeToken = std::string("SIG_VALTYPE_");
00049   }
00050 
00051   DbcBuilder::~DbcBuilder()
00052   {
00053   }
00054 
00055   NewEagle::Dbc DbcBuilder::NewDbc(const std::string &dbcFile)
00056   {
00057 
00058     NewEagle::Dbc dbc;
00059 
00060     std::istringstream f(dbcFile);
00061     std::string line;
00062     uint32_t lineNumber = 0;
00063 
00064     NewEagle::DbcMessage currentMessage;
00065 
00066     int32_t cnt = 0;
00067 
00068     while (std::getline(f, line, '\n'))
00069     {
00070       lineNumber++;
00071 
00072       NewEagle::LineParser parser(line);
00073 
00074 
00075       std::string identifier;
00076       try
00077       {
00078         identifier = parser.ReadCIdentifier();
00079       }
00080       catch(std::exception& ex)
00081       {
00082         identifier = std::string();
00083       }
00084 
00085       if (!MessageToken.compare(identifier))
00086       {
00087         try
00088         {
00089           currentMessage =  ReadMessage(parser);
00090           currentMessage.SetRawText(line);
00091           dbc.AddMessage(currentMessage.GetName(), currentMessage);
00092         }
00093         catch(LineParserExceptionBase& exlp)
00094         {
00095           ROS_WARN("LineParser Exception: [%s]", exlp.what());
00096         }
00097         catch(std::exception& ex)
00098         {
00099           ROS_ERROR("DBC Message Parser Exception: [%s]", ex.what());
00100         }
00101       }
00102       else if (!SignalToken.compare(identifier))
00103       {
00104         try
00105         {
00106           NewEagle::DbcSignal signal = ReadSignal(parser);
00107 
00108           NewEagle::DbcMessage* msg = dbc.GetMessage(currentMessage.GetName());
00109           msg->AddSignal(signal.GetName(), signal);
00110         }
00111         catch(LineParserExceptionBase& exlp)
00112         {
00113           ROS_WARN("LineParser Exception: [%s]", exlp.what());
00114         }
00115         catch(std::exception& ex)
00116         {
00117           ROS_ERROR("DBC Signal Parser Exception: [%s]", ex.what());
00118         }
00119       }
00120       else if (!CommentToken.compare(identifier))
00121       {
00122         try
00123         {
00124           std::string token = parser.ReadCIdentifier();
00125 
00126           if (!MessageToken.compare(token))
00127           {
00128             NewEagle::DbcMessageComment dbcMessageComment = ReadMessageComment(parser);
00129 
00130             std::map<std::string, NewEagle::DbcMessage>::iterator it;
00131             int32_t ttt = 0;
00132 
00133             for (it = dbc.GetMessages()->begin(); it != dbc.GetMessages()->end(); ++it)
00134             {
00135               ttt++;
00136               if (it->second.GetRawId() == dbcMessageComment.Id)
00137               {
00138                 it->second.SetComment(dbcMessageComment);
00139                 break;
00140               }
00141             }
00142           }
00143           else if (!SignalToken.compare(token))
00144           {
00145             NewEagle::DbcSignalComment dbcSignalComment = ReadSignalComment(parser);
00146 
00147             std::map<std::string, NewEagle::DbcMessage>::iterator it;
00148             for (it = dbc.GetMessages()->begin(); it != dbc.GetMessages()->end(); ++it)
00149             {
00150               if (it->second.GetRawId() == dbcSignalComment.Id)
00151               {
00152                 DbcMessage msg = it->second;
00153                 std::map<std::string, NewEagle::DbcSignal>::iterator its;
00154 
00155                 for (its = msg.GetSignals()->begin(); its != msg.GetSignals()->end(); ++its)
00156                 {
00157                   if (its->second.GetName() == dbcSignalComment.SignalName)
00158                   {
00159                     its->second.SetComment(dbcSignalComment);
00160                     break;
00161                   }
00162                 }
00163               }
00164             }
00165           }
00166         }
00167         catch(LineParserExceptionBase& exlp)
00168         {
00169           ROS_WARN("LineParser Exception: [%s]", exlp.what());
00170         }
00171         catch(std::exception& ex)
00172         {
00173           ROS_ERROR("DBC Comment Parser Exception: [%s]", ex.what());
00174         }
00175       }
00176       else if (!AttributeToken.compare(identifier))
00177       {
00178         try
00179         {
00180           NewEagle::DbcAttribute dbcAttribute = ReadAttribute(parser);
00181 
00182           if (dbc.GetMessageCount() > 0)
00183           {
00184             std::map<std::string, NewEagle::DbcMessage>::iterator it;
00185             for (it = dbc.GetMessages()->begin(); it != dbc.GetMessages()->end(); ++it)
00186             {
00187               if (it->second.GetRawId() == dbcAttribute.Id)
00188               {
00189                 std::map<std::string, NewEagle::DbcSignal>::iterator its;
00190                 DbcMessage msg = it->second;
00191                 for (its = msg.GetSignals()->begin(); its != msg.GetSignals()->end(); ++its)
00192                 {
00193                   if (its->second.GetName() == dbcAttribute.SignalName)
00194                   {
00195                     NewEagle::DbcSignal sig = its->second;
00196 
00197                     double gain = sig.GetGain();
00198                     double offset = sig.GetOffset();
00199 
00200                     double f = 0.0;
00201 
00202                     std::stringstream ss;
00203                     ss << dbcAttribute.Value;
00204                     ss >> f;
00205 
00206                     double val = gain * f + offset;
00207                     sig.SetInitialValue(val);
00208                     break;
00209                   }
00210                 }
00211               }
00212             }
00213           }
00214         }
00215         catch(LineParserExceptionBase& exlp)
00216         {
00217           ROS_WARN("LineParser Exception: [%s]", exlp.what());
00218         }
00219         catch(std::exception& ex)
00220         {
00221           ROS_ERROR("DBC Signal Value Type Parser Exception: [%s]", ex.what());
00222         }
00223       }
00224       else if (!EnumValueToken.compare(identifier))
00225       {
00226         // Empty for now.
00227       }
00228       else if (!SignalValueTypeToken.compare(identifier))
00229       {
00230         try
00231         {
00232           NewEagle::DbcSignalValueType dbcSignalValueType = ReadSignalValueType(parser);
00233 
00234           if (dbc.GetMessageCount() > 0)
00235           {
00236             std::map<std::string, NewEagle::DbcMessage>::iterator it;
00237             for (it = dbc.GetMessages()->begin(); it != dbc.GetMessages()->end(); ++it)
00238             {
00239               if (it->second.GetRawId() == dbcSignalValueType.Id)
00240               {
00241                 std::map<std::string, NewEagle::DbcSignal>::iterator its;
00242                 DbcMessage msg = it->second;
00243                 for (its = msg.GetSignals()->begin(); its != msg.GetSignals()->end(); ++its)
00244                 {
00245                   if (its->second.GetName() == dbcSignalValueType.SignalName)
00246                   {
00247                     NewEagle::DbcSignal sig = its->second;
00248                     sig.SetDataType(dbcSignalValueType.Type);
00249                     break;
00250                   }
00251                 }
00252               }
00253             }
00254           }
00255         }
00256         catch(LineParserExceptionBase& exlp)
00257         {
00258           ROS_WARN("LineParser Exception: [%s]", exlp.what());
00259         }
00260         catch(std::exception& ex)
00261         {
00262           ROS_ERROR("DBC Signal Value Type Parser Exception: [%s]", ex.what());
00263         }
00264 
00265       }
00266     }
00267 
00268     ROS_INFO("dbc.size() = %d", dbc.GetMessageCount());
00269 
00270     return dbc;
00271   }
00272 }


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