DbcSignal.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/DbcSignal.h>
00036 
00037 namespace NewEagle
00038 {
00039   DbcSignal::DbcSignal(
00040     uint8_t dlc,
00041     double gain,
00042     double offset,
00043     uint8_t startBit,
00044     ByteOrder endianness,
00045     uint8_t length,
00046     SignType sign,
00047     std::string name,
00048     MultiplexerMode multiplexerMode)
00049   {
00050     _dlc = dlc;
00051     _gain  = gain;
00052     _offset = offset;
00053     _startBit = startBit;
00054     _endianness = endianness;
00055     _length = length;
00056     _sign = sign;
00057     _name = name;
00058     _multiplexerMode = multiplexerMode;
00059   }
00060 
00061   DbcSignal::DbcSignal(
00062     uint8_t dlc,
00063     double gain,
00064     double offset,
00065     uint8_t startBit,
00066     ByteOrder endianness,
00067     uint8_t length,
00068     SignType sign,
00069     std::string name,
00070     MultiplexerMode multiplexerMode,
00071     int32_t multiplexerSwitch)
00072   {
00073     _dlc = dlc;
00074     _gain  = gain;
00075     _offset = offset;
00076     _startBit = startBit;
00077     _endianness = endianness;
00078     _length = length;
00079     _sign = sign;
00080     _name = name;
00081     _multiplexerMode = multiplexerMode;
00082     _multiplexerSwitch = multiplexerSwitch;
00083   }
00084 
00085   DbcSignal::~DbcSignal()
00086   {
00087   }
00088 
00089   uint8_t DbcSignal::GetDlc() const
00090   {
00091     return _dlc;
00092   }
00093 
00094   double DbcSignal::GetResult() const
00095   {
00096     return _result;
00097   }
00098 
00099   double DbcSignal::GetGain() const
00100   {
00101     return _gain;
00102   }
00103 
00104   double DbcSignal::GetOffset() const
00105   {
00106     return _offset;
00107   }
00108 
00109   uint8_t DbcSignal::GetStartBit() const
00110   {
00111     return _startBit;
00112   }
00113 
00114   ByteOrder DbcSignal::GetEndianness() const
00115   {
00116     return _endianness;
00117   }
00118 
00119   uint8_t DbcSignal::GetLength() const
00120   {
00121     return _length;
00122   }
00123 
00124   SignType DbcSignal::GetSign() const
00125   {
00126     return _sign;
00127   }
00128 
00129   std::string DbcSignal::GetName() const
00130   {
00131     return _name;
00132   }
00133 
00134   void DbcSignal::SetResult(double result)
00135   {
00136     _result = result;
00137   }
00138 
00139   void DbcSignal::SetComment(NewEagle::DbcSignalComment comment)
00140   {
00141     _comment = comment;
00142   }
00143 
00144   void DbcSignal::SetInitialValue(double value)
00145   {
00146     _initialValue = value;
00147   }
00148   double DbcSignal::GetInitialValue()
00149   {
00150     return _initialValue;
00151   }
00152 
00153   void DbcSignal::SetDataType(NewEagle::DataType type)
00154   {
00155     _type = type;
00156   }
00157 
00158   NewEagle::DataType DbcSignal::GetDataType()
00159   {
00160     return _type;
00161   }
00162 
00163   NewEagle::MultiplexerMode DbcSignal::GetMultiplexerMode() const
00164   {
00165     return _multiplexerMode;
00166   }
00167 
00168   int32_t DbcSignal::GetMultiplexerSwitch() const
00169   {
00170     return _multiplexerSwitch;
00171   }
00172 }


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