DbcSignal.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015-2018, Dataspeed Inc.
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 Dataspeed Inc. 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 _DBC_SIGNAL_HPP
00036 #define _DBC_SIGNAL_HPP
00037 
00038 #include <string>
00039 #include <iosfwd>
00040 #include <set>
00041 
00042 typedef enum {
00043   MOTOROLA,
00044   INTEL
00045 } ByteOrder;
00046 
00047 typedef enum {
00048   UNSIGNED,
00049   SIGNED
00050 } Sign;
00051 
00052 typedef enum {
00053   NONE,
00054   MULTIPLEXED,
00055   MULTIPLEXOR
00056 } Multiplexor;
00057 
00058 
00064 class Signal {
00065 
00066   typedef std::set<std::string> toList;
00067   // The name of the Signal in the DBC-File
00068   std::string name;
00069   // The Byteorder of the Signal (@see: endianess)
00070   ByteOrder order;
00071   // The Startbit inside the Message of this Signal. Allowed values are 0-63
00072   unsigned short startBit;
00073   // The Length of the Signal. It can be anything between 1 and 64
00074   unsigned short length;
00075   // If the Data contained in the Signal is signed or unsigned Data
00076   Sign sign;
00077   // Depending on the information given above one can calculate the minimum of this Signal
00078   double minimum;
00079   // Depending on the information given above one can calculate the maximum of this Signal
00080   double maximum;
00081   // The Factor for calculating the physical value: phys = digits * factor + offset
00082   double factor;
00083   // The offset for calculating the physical value: phys = digits * factor + offset
00084   double offset;
00085   // String containing an associated unit.
00086   std::string unit;
00087   // Contains weather the Signal is Multiplexed and if it is, multiplexNum contains multiplex number
00088   Multiplexor multiplexor;
00089   // Contains the multiplex Number if the Signal is multiplexed
00090   unsigned short multiplexNum;
00091   // Contains to which Control Units in the CAN-Network the Signal shall be sent
00092   toList to;
00093 
00094 public:
00095   // Overload of operator>> to allow parsing from DBC Streams
00096   friend std::istream& operator>>(std::istream& in, Signal& sig);
00097 
00098   // Getter for all the Values contained in a Signal
00099   const std::string& getName() const { return name; }
00100   ByteOrder getByteOrder() const { return order; }
00101   unsigned short getStartbit() const { return startBit; }
00102   unsigned short getLength() const { return length; }
00103   Sign getSign() const { return sign; }
00104   double getMinimum() const { return minimum; }
00105   double getMaximum() const { return maximum; }
00106   double getFactor() const { return factor; }
00107   double getOffset() const { return offset; }
00108   const std::string& getUnit() const { return unit; }
00109   Multiplexor getMultiplexor() const { return multiplexor; }
00110   unsigned short getMultiplexedNumber() const { return multiplexNum; }
00111   const toList& getTo() const { return to; }
00112 
00113 };
00114 
00115 #endif /* _DBC_SIGNAL_HPP */
00116 


dataspeed_can_tools
Author(s): Micho Radovnikovich
autogenerated on Thu Jun 6 2019 21:16:41