DbcMessage.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/DbcMessage.h>
00036 
00037 #include "DbcUtilities.h"
00038 
00039 namespace NewEagle
00040 {
00041   DbcMessage::DbcMessage()
00042   {
00043   };
00044 
00045   DbcMessage::DbcMessage(
00046     uint8_t dlc,
00047     uint32_t id,
00048     IdType idType,
00049     std::string name,
00050     uint32_t rawId)
00051   {
00052     _dlc = dlc;
00053     _id = id;
00054     _idType = idType;
00055     _name = name;
00056     _rawId = rawId;
00057   }
00058 
00059   DbcMessage::~DbcMessage()
00060   {
00061   }
00062 
00063   uint8_t DbcMessage::GetDlc()
00064   {
00065     return _dlc;
00066   }
00067 
00068   uint32_t DbcMessage::GetId()
00069   {
00070     return _id;
00071   }
00072 
00073   uint32_t DbcMessage::GetRawId()
00074   {
00075     return _rawId;
00076   }
00077 
00078   IdType DbcMessage::GetIdType()
00079   {
00080     return _idType;
00081   }
00082 
00083   std::string DbcMessage::GetName()
00084   {
00085     return _name;
00086   }
00087 
00088   can_msgs::Frame DbcMessage::GetFrame()
00089   {
00090     can_msgs::Frame frame;
00091 
00092     frame.id = _id;
00093     frame.dlc = _dlc;
00094     frame.is_extended = _idType == EXT;
00095 
00096     uint8_t *ptr = (uint8_t*)frame.data.elems;
00097     memset(ptr, 0x00, 8);
00098 
00099     if(!AnyMultiplexedSignals()) {
00100       for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++) {
00101         Pack(ptr, it->second);
00102       }    
00103     }
00104     else{
00105       // Start by looping through an only setting signals that are not multiplexed
00106       // While we're at it, we can pick out the mutliplexer switch.  
00107       // Perform a second loop to find the mulitplexed signal based on the multiplexer switch.
00108             
00109       NewEagle::DbcSignal* muxSwitch; // only one multiplexer switch per message is allowed
00110 
00111       for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++) {
00112         if (NewEagle::NONE == it->second.GetMultiplexerMode()) {
00113           Pack(ptr, it->second);
00114         }                
00115         if (NewEagle::MUX_SWITCH == it->second.GetMultiplexerMode()) {
00116           muxSwitch = &it->second;
00117           Pack(ptr, it->second);
00118         }
00119       }  
00120 
00121       for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++) {
00122         if (NewEagle::MUX_SIGNAL == it->second.GetMultiplexerMode()) {
00123           if (muxSwitch->GetResult() == it->second.GetMultiplexerSwitch()) {
00124             Pack(ptr, it->second);
00125           }
00126 
00127         }                  
00128       }
00129     }
00130 
00131     return frame;
00132   }
00133 
00134   void DbcMessage::SetFrame(const can_msgs::Frame::ConstPtr& msg)
00135   {
00136     uint8_t *ptr = (uint8_t*)msg->data.elems;
00137 
00138     if(!AnyMultiplexedSignals()) {
00139       for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++) {
00140         double res = Unpack(ptr, it->second);
00141         it->second.SetResult(res);
00142       }
00143     }
00144     else{
00145       // Start by looping through an only setting signals that are not multiplexed
00146       // While we're at it, we can pick out the mutliplexer switch.  
00147       // Perform a second loop to find the mulitplexed signal based on the multiplexer switch.
00148             
00149       NewEagle::DbcSignal* muxSwitch; // only one multiplexer switch per message is allowed
00150 
00151       for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++) {
00152         if (NewEagle::NONE == it->second.GetMultiplexerMode()) {
00153           double res = Unpack(ptr, it->second);
00154           it->second.SetResult(res);
00155         }                
00156         if (NewEagle::MUX_SWITCH == it->second.GetMultiplexerMode()) {
00157           muxSwitch = &it->second;
00158           double res = Unpack(ptr, it->second);
00159           it->second.SetResult(res);
00160         }
00161       }  
00162 
00163       for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++) {
00164         if (NewEagle::MUX_SIGNAL == it->second.GetMultiplexerMode()) {
00165           if (muxSwitch->GetResult() == it->second.GetMultiplexerSwitch()) {
00166             double res = Unpack(ptr, it->second);
00167             it->second.SetResult(res);
00168           }
00169 
00170         }                  
00171       }
00172     }    
00173 
00174   }
00175 
00176   void DbcMessage::AddSignal(std::string signalName, NewEagle::DbcSignal signal)
00177   {
00178     _signals.insert(std::pair<std::string, NewEagle::DbcSignal>(signalName, signal));
00179   }
00180 
00181   NewEagle::DbcSignal* DbcMessage::GetSignal(std::string signalName)
00182   {
00183     std::map<std::string, NewEagle::DbcSignal>::iterator it;
00184 
00185     it = _signals.find(signalName);
00186 
00187     if (_signals.end() == it)
00188     {
00189       return NULL;
00190     }
00191 
00192     NewEagle::DbcSignal* signal = &it->second;
00193 
00194     return signal;
00195   }
00196 
00197   void DbcMessage::SetRawText(std::string rawText)
00198   {
00199 
00200   }
00201 
00202   uint32_t DbcMessage::GetSignalCount()
00203   {
00204     return _signals.size();
00205   }
00206 
00207   void DbcMessage::SetComment(NewEagle::DbcMessageComment comment)
00208   {
00209     _comment = comment;
00210   }
00211 
00212   std::map<std::string, NewEagle::DbcSignal>* DbcMessage::GetSignals()
00213   {
00214     return &_signals;
00215   }
00216 
00217   bool DbcMessage::AnyMultiplexedSignals()
00218   {
00219     for(std::map<std::string, NewEagle::DbcSignal>::iterator it = _signals.begin(); it != _signals.end(); it++)
00220     {
00221       if (NewEagle::MUX_SWITCH == it->second.GetMultiplexerMode())
00222       {
00223         return true;
00224       }
00225     }
00226 
00227     return false;
00228   }
00229 }


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