DbcUtilities.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_DBC_UTILITIES_H
00036 #define _NEW_EAGLE_DBC_UTILITIES_H
00037 
00038 #include <ros/ros.h>
00039 #include <map>
00040 #include <sstream>      // std::istringstream
00041 #include <string>
00042 
00043 #include <dbc/DbcSignal.h>
00044 #include <dbc/DbcMessage.h>
00045 
00046 namespace NewEagle
00047 {
00048   static int32_t ConvertToMTBitOrdering(uint32_t bit, uint32_t dlc)
00049   {
00050     if (bit < 0 || bit >- dlc * 8)
00051     {
00052       return -1;
00053     }
00054 
00055     int32_t msgBitLength = (int32_t)dlc * 8;
00056 
00057     int32_t row = (int32_t) bit / 8;
00058     int32_t offset = (int32_t)bit % 8;
00059 
00060     return (msgBitLength - (row + 1) * 8) + offset;
00061   }
00062 
00063   static int32_t ConvertToMTBitOrdering(uint32_t bit)
00064   {
00065     return ConvertToMTBitOrdering(bit, 8);
00066 
00067   }
00068 
00069   static double Unpack(uint8_t* data, const NewEagle::DbcSignal &signal)
00070   {
00071     int32_t wordSize = sizeof(data);
00072     int32_t startBit = (int32_t)signal.GetStartBit();
00073 
00074     if (signal.GetEndianness() == NewEagle::LITTLE_END)
00075     {
00076       startBit = ConvertToMTBitOrdering(signal.GetStartBit(), signal.GetDlc());
00077     }
00078     else
00079     {
00080       startBit = ConvertToMTBitOrdering(signal.GetStartBit(), signal.GetDlc()) - ((int32_t)signal.GetLength() - 1);
00081     }
00082 
00083     int32_t bit = (int32_t)(startBit % 8);
00084 
00085     bool isExactlyByte = ((bit + signal.GetLength()) % 8 == 0);
00086     uint32_t numBytes = (isExactlyByte ? 0 : 1) + ((bit + (int32_t)signal.GetLength()) / 8);
00087 
00088     int32_t b = (int32_t)wordSize - ((int)startBit / 8) - 1;
00089     int32_t w = (int)signal.GetLength();
00090     int32_t maskShift = bit;
00091     int32_t rightShift = 0;
00092 
00093     uint32_t unsignedResult = 0;
00094     for(int32_t i = 0; i < numBytes; i++)
00095     {
00096       if ((b < 0) || (b >= sizeof(data)))
00097       {
00098         return std::numeric_limits<int>::quiet_NaN();
00099       }
00100 
00101       int32_t mask = 0xFF;
00102       if (w < 8)
00103       {
00104         mask >>= (8 - w);
00105       }
00106       mask <<= maskShift;
00107 
00108       int32_t extractedByte = (data[b] & mask) >> maskShift;
00109       unsignedResult |= (uint32_t)extractedByte << (8 * i - rightShift);
00110 
00111       if (signal.GetEndianness() == NewEagle::BIG_END)
00112       {
00113         if ((b % wordSize) == 0)
00114         {
00115           b += 2 * wordSize - 1;
00116         }
00117         else
00118         {
00119           b--;
00120         }
00121       }
00122       else
00123       {
00124         b++;
00125       }
00126       
00127       w -= ( 8 - maskShift);
00128       rightShift += maskShift;
00129       maskShift = 0;
00130 
00131     }
00132 
00133     double result = 0;
00134     if (signal.GetSign() == NewEagle::SIGNED)
00135     {
00136       if ((unsignedResult & (1 << (int32_t)signal.GetLength() - 1)) != 0)
00137       {
00138         if (signal.GetLength() < 32)
00139         {
00140           uint32_t signExtension = (0xFFFFFFFF << (int32_t)signal.GetLength());
00141           unsignedResult |= signExtension;
00142         }
00143       }
00144 
00145       result = (double)((int32_t)unsignedResult);
00146 
00147     }
00148     else if (signal.GetSign() == NewEagle::UNSIGNED)
00149     {
00150       result = (double)(unsignedResult);
00151     }
00152 
00153     if ((signal.GetGain() != 1) || (signal.GetOffset() != 0))
00154     {
00155       result *= signal.GetGain();
00156       result += signal.GetOffset();
00157     }
00158 
00159     return result;
00160   }
00161 
00162   static void Pack(uint8_t * data, const NewEagle::DbcSignal &signal)
00163   {
00164     uint32_t result = 0;
00165 
00166     double tmp = signal.GetResult();
00167 
00168     if ((signal.GetGain() != 1) || (signal.GetOffset() != 0))
00169     {
00170       tmp -= signal.GetOffset();
00171       tmp /= signal.GetGain();
00172     }
00173 
00174     if (signal.GetSign() == NewEagle::SIGNED)
00175     {
00176       int32_t i = (int32_t)tmp;
00177       uint32_t u = (uint)i;
00178 
00179       result = u;
00180     }
00181     else
00182     {
00183       result = (uint)tmp;
00184     }
00185 
00186     int8_t wordSize = sizeof(data);
00187     int8_t startBit = (int)signal.GetStartBit();
00188 
00189     if (signal.GetEndianness() == NewEagle::LITTLE_END)
00190     {
00191       startBit = ConvertToMTBitOrdering(signal.GetStartBit(), signal.GetDlc());
00192     }
00193     else
00194     {
00195       startBit = ConvertToMTBitOrdering(signal.GetStartBit(), signal.GetDlc()) - ((int32_t)signal.GetLength() - 1);
00196     }
00197 
00198     int32_t bit = (int32_t)(startBit % 8);
00199 
00200     bool isExactlyByte = ((bit + signal.GetLength()) % 8 == 0);
00201     uint32_t numBytes = (isExactlyByte ? 0 : 1) + ((bit + (int32_t)signal.GetLength()) / 8);
00202 
00203     int32_t b = (int32_t)wordSize - ((int)startBit / 8) - 1;
00204     int32_t w = (int)signal.GetLength();
00205     int32_t maskShift = bit;
00206     int32_t rightShift = 0;
00207 
00208     uint8_t mask = 0xFF;
00209     uint32_t extractedByte;
00210 
00211     for(int i = 0; i < numBytes; i++)
00212     {
00213       if ((b < 0 || (b >= sizeof(data))))
00214       {
00215         return;
00216       }
00217 
00218       mask = 0xFF;
00219 
00220       if (w < 8)
00221       {
00222         mask >>= (8 - w);
00223       }
00224 
00225       mask <<= maskShift;
00226 
00227       extractedByte = (result >> (8 * i - rightShift)) & 0xFF;
00228 
00229       data[b] = (uint32_t)(data[b] & ~mask);
00230       data[b] |= (uint8_t)((extractedByte << maskShift) & mask);
00231 
00232       if (signal.GetEndianness() == NewEagle::BIG_END)
00233       {
00234         if ((b % wordSize) == 0)
00235         {
00236           b += 2 * wordSize - 1;
00237         }
00238         else
00239         {
00240           b--;
00241         }
00242       }
00243       else
00244       {
00245         b++;
00246       }
00247 
00248       w -= ( 8 - maskShift);
00249       rightShift += maskShift;
00250       maskShift = 0;
00251     }
00252 
00253   }
00254 
00255 }
00256 
00257 #endif // _NEW_EAGLE_DBC_UTILITIES_H


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