byte_array.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2015, Southwest Research Institute
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 are met:
00009  *
00010  *       * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *       * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *       * Neither the name of the Southwest Research Institute, nor the names
00016  *       of its contributors may be used to endorse or promote products derived
00017  *       from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 #ifndef FLATHEADERS
00032 #include "simple_message/byte_array.h"
00033 #include "simple_message/simple_serialize.h"
00034 #include "simple_message/log_wrapper.h"
00035 #else
00036 #include "byte_array.h"
00037 #include "simple_serialize.h"
00038 #include "log_wrapper.h"
00039 #endif
00040 
00041 namespace industrial
00042 {
00043 namespace byte_array
00044 {
00045 
00046 using namespace industrial::simple_serialize;
00047 using namespace industrial::shared_types;
00048 using namespace industrial::byte_array;
00049 
00050 ByteArray::ByteArray(void)
00051 {
00052   this->init();
00053 #ifdef BYTE_SWAPPING
00054   LOG_COMM("Byte swapping enabled");
00055 #endif
00056 }
00057 
00058 ByteArray::~ByteArray(void)
00059 {
00060 }
00061 
00062 void ByteArray::init()
00063 {
00064   this->buffer_.clear();
00065 }
00066 
00067 bool ByteArray::init(const char* buffer, const shared_int byte_size)
00068 {
00069   bool rtn;
00070 
00071   if (this->getMaxBufferSize() >= byte_size)
00072   {
00073     LOG_COMM("Initializing buffer to size: %d", byte_size);
00074     this->load((void*)buffer, byte_size);
00075     rtn = true;
00076   }
00077   else
00078   {
00079     LOG_ERROR("Failed to initialize byte array, buffer size: %u greater than max: %u",
00080               byte_size, this->getMaxBufferSize());
00081     rtn = false;
00082   }
00083   return rtn;
00084 }
00085 
00086 void ByteArray::copyFrom(ByteArray & buffer)
00087 {
00088   if (buffer.getBufferSize() != 0)
00089   {
00090     this->buffer_ = buffer.buffer_;
00091   }
00092   else
00093   {
00094     LOG_WARN("Byte array copy not performed, buffer to copy is empty");
00095   }
00096 }
00097 
00098 void ByteArray::copyTo(std::vector<char> &out)
00099 {
00100   out.assign(buffer_.begin(), buffer_.end());
00101 }
00102 
00103 
00104 #ifdef BYTE_SWAPPING
00105 void ByteArray::swap(void *value, shared_int byteSize)
00106 {
00107   LOG_COMM("Executing byte swapping");
00108 
00109   LOG_COMM("Value (swapping-input): %u", (unsigned int)(*(unsigned int*)value));
00110   for (unsigned int i = 0; i < byteSize / 2; i++)
00111   {
00112     unsigned int endIndex = byteSize - i - 1;
00113     char endByte = ((char*)value)[endIndex];
00114     unsigned int endInt = endByte;
00115 
00116     unsigned int beginIndex = i;
00117     char beginByte = ((char*)value)[beginIndex];
00118     unsigned int beginInt = beginByte;
00119 
00120     LOG_COMM("Swap beginIndex i: %u, endIndex: %u, begin[]: %u, end[]: %u",
00121              beginIndex, endIndex, beginInt, endInt);
00122     ((char*)value)[endIndex] = beginByte;
00123     ((char*)value)[beginIndex] = endByte;
00124   }
00125   LOG_COMM("Value (swapping-output): %u", (unsigned int)(*(unsigned int*)value));
00126 
00127 }
00128 #endif
00129 
00130 char* ByteArray::getRawDataPtr()
00131 {
00132   this->copyTo( this->getRawDataPtr_buffer_ );
00133   return &getRawDataPtr_buffer_[0];
00134 }
00135 
00136 /****************************************************************
00137  // load(*)
00138  //
00139  // Methods for loading various data types.
00140  //
00141  */
00142 bool ByteArray::load(shared_bool value)
00143 {
00144   return this->load(&value, sizeof(shared_bool));
00145 }
00146 
00147 bool ByteArray::load(shared_real value)
00148 {
00149 #ifdef BYTE_SWAPPING
00150   LOG_COMM("Value (loading-input): %f", value);
00151   this->swap(&value, sizeof(shared_real));
00152   LOG_COMM("Value (loading-output): %f", value);
00153 #endif
00154 
00155   return this->load(&value, sizeof(shared_real));
00156 }
00157 
00158 bool ByteArray::load(shared_int value)
00159 {
00160 #ifdef BYTE_SWAPPING
00161   LOG_COMM("Value (loading-input): %d", value);
00162   this->swap(&value, sizeof(shared_int));
00163   LOG_COMM("Value (loading-output): %d", value);
00164 #endif
00165 
00166   return this->load(&value, sizeof(shared_int));
00167 }
00168 
00169 bool ByteArray::load(simple_serialize::SimpleSerialize &value)
00170 {
00171   LOG_COMM("Executing byte array load through simple serialize");
00172   return value.load(this);
00173 }
00174 
00175 bool ByteArray::load(ByteArray &value)
00176 {
00177   LOG_COMM("Executing byte array load through byte array");
00178   std::deque<char>& src = value.buffer_;
00179   std::deque<char>& dest  = this->buffer_;
00180 
00181   if (this->getBufferSize()+value.getBufferSize() > this->getMaxBufferSize())
00182   {
00183     LOG_ERROR("Additional data would exceed buffer size");
00184     return false;
00185   }
00186 
00187   dest.insert(dest.end(), src.begin(), src.end());
00188   return true;
00189 }
00190 
00191 bool ByteArray::load(void* value, const shared_int byte_size)
00192 {
00193 
00194   bool rtn;
00195 
00196   LOG_COMM("Executing byte array load through void*, size: %d", byte_size);
00197   // Check inputs
00198   if (NULL == value)
00199   {
00200     LOG_ERROR("NULL point passed into load method");
00201     return false;
00202   }
00203   if (this->getBufferSize()+byte_size > this->getMaxBufferSize())
00204   {
00205     LOG_ERROR("Additional data would exceed buffer size");
00206     return false;
00207   }
00208 
00209   try
00210   {
00211     char* bytePtr = (char*)value;
00212     this->buffer_.insert(this->buffer_.end(), bytePtr, bytePtr + byte_size);
00213 
00214     rtn = true;
00215   }
00216   catch (std::exception)
00217   {
00218     LOG_ERROR("Failed to load byte array");
00219     rtn = false;
00220   }
00221 
00222   return rtn;
00223 }
00224 
00225 /****************************************************************
00226  // unload(*)
00227  //
00228  // Methods for unloading various data types.  Unloading data shortens
00229  // the internal buffer.  The resulting memory that holds the data is
00230  // lost.
00231  //
00232  */
00233 bool ByteArray::unload(shared_bool & value)
00234 {
00235   shared_bool rtn = this->unload(&value, sizeof(shared_bool));
00236   return rtn;
00237 
00238 }
00239 
00240 bool ByteArray::unload(shared_real &value)
00241 {
00242   bool rtn = this->unload(&value, sizeof(shared_real));
00243 
00244 #ifdef BYTE_SWAPPING
00245   LOG_COMM("Value (unloading-input): %f", value);
00246   this->swap(&value, sizeof(shared_real));
00247   LOG_COMM("Value (unloading-output): %f", value);
00248 #endif
00249 
00250   return rtn;
00251 }
00252 
00253 bool ByteArray::unload(shared_int &value)
00254 {
00255   bool rtn = this->unload(&value, sizeof(shared_int));
00256 
00257 #ifdef BYTE_SWAPPING
00258   LOG_COMM("Value (unloading-input): %d", value);
00259   this->swap(&value, sizeof(shared_int));
00260   LOG_COMM("Value (unloading-output): %d", value);
00261 #endif
00262   return rtn;
00263 }
00264 
00265 bool ByteArray::unload(simple_serialize::SimpleSerialize &value)
00266 {
00267   LOG_COMM("Executing byte array unload through simple serialize");
00268   return value.unload(this);
00269 }
00270 
00271 
00272 bool ByteArray::unload(ByteArray &value, const shared_int byte_size)
00273 {
00274   LOG_COMM("Executing byte array unload through byte array");
00275   bool rtn;
00276 
00277   if (byte_size <= this->getBufferSize())
00278   {
00279     std::deque<char>& src  = this->buffer_;
00280     std::deque<char>& dest = value.buffer_;
00281 
00282     dest.insert(dest.end(), src.end()-byte_size, src.end());
00283     src.erase(src.end()-byte_size, src.end());
00284     rtn = true;
00285   }
00286   else
00287   {
00288     LOG_ERROR("Buffer smaller than requested size.");
00289     rtn = false;
00290   }
00291 
00292   return rtn;
00293 }
00294 
00295 bool ByteArray::unload(void* value, shared_int byteSize)
00296 {
00297   bool rtn;
00298 
00299   LOG_COMM("Executing byte array unload through void*, size: %d", byteSize);
00300   // Check inputs
00301   if (NULL == value)
00302   {
00303     LOG_ERROR("NULL point passed into unload method");
00304     return false;
00305   }
00306 
00307   if (byteSize <= this->getBufferSize())
00308   {
00309       std::deque<char>& src  = this->buffer_;
00310 
00311       std::copy(src.end()-byteSize, src.end(), (char*)value);
00312       src.erase(src.end()-byteSize, src.end());
00313       rtn = true;
00314   }
00315   else
00316   {
00317     LOG_ERROR("Buffer is smaller than requested byteSize.");
00318     rtn = false;
00319   }
00320 
00321   return rtn;
00322 }
00323 
00324 
00325 
00326 /****************************************************************
00327  // unloadFront(*)
00328  //
00329  // Methods for unloading various data types.  Unloading data shortens
00330  // the internal buffer and requires a memmove.  These functions should
00331  // be used sparingly, as they are expensive.
00332  //
00333  */
00334 bool ByteArray::unloadFront(industrial::shared_types::shared_real &value)
00335 {
00336   bool rtn = this->unloadFront(&value, sizeof(shared_real));
00337 
00338 #ifdef BYTE_SWAPPING
00339   LOG_COMM("Value (unloading-input): %f", value);
00340   this->swap(&value, sizeof(shared_real));
00341   LOG_COMM("Value (unloading-output): %f", value);
00342 #endif
00343   return rtn;
00344 }
00345 
00346 bool ByteArray::unloadFront(industrial::shared_types::shared_int &value)
00347 {
00348   bool rtn = this->unloadFront(&value, sizeof(shared_int));
00349 
00350 #ifdef BYTE_SWAPPING
00351   LOG_COMM("Value (unloading-input): %d", value);
00352   this->swap(&value, sizeof(shared_int));
00353   LOG_COMM("Value (unloading-output): %d", value);
00354 #endif
00355   return rtn;
00356 }
00357 
00358 bool ByteArray::unloadFront(void* value, const industrial::shared_types::shared_int byteSize)
00359 {
00360   bool rtn;
00361 
00362   LOG_COMM("Executing byte array unloadFront through void*, size: %d", byteSize);
00363   // Check inputs
00364   if (NULL == value)
00365   {
00366     LOG_ERROR("NULL point passed into unloadFront method");
00367     return false;
00368   }
00369 
00370   if (byteSize <= this->getBufferSize())
00371   {
00372       std::deque<char>& src  = this->buffer_;
00373 
00374       std::copy(src.begin(), src.begin()+byteSize, (char*)value);
00375       src.erase(src.begin(), src.begin()+byteSize);
00376       rtn = true;
00377   }
00378   else
00379   {
00380     LOG_ERROR("Buffer is smaller than requested byteSize.");
00381     rtn = false;
00382   }
00383 
00384   return rtn;
00385 }
00386 
00387 unsigned int ByteArray::getBufferSize()
00388 {
00389   return this->buffer_.size();
00390 }
00391 
00392 unsigned int ByteArray::getMaxBufferSize()
00393 {
00394   return this->buffer_.max_size();
00395 }
00396 
00397 
00398 bool ByteArray::isByteSwapEnabled()
00399 {
00400 #ifdef BYTE_SWAPPING
00401   return true;
00402 #endif
00403   return false;
00404 }
00405 
00406 } // namespace byte_array
00407 } // namespace industrial


simple_message
Author(s): Shaun Edwards
autogenerated on Tue Jan 17 2017 21:10:02