BufferStream.hh
Go to the documentation of this file.
00001 
00039 #ifndef CRL_MULTISENSE_BUFFERSTREAM_HH
00040 #define CRL_MULTISENSE_BUFFERSTREAM_HH
00041 
00042 #include "Exception.hh"
00043 #include "TimeStamp.hh"
00044 #include "ReferenceCount.hh"
00045 #include "Portability.hh"
00046 
00047 #include <stdint.h>
00048 #include <cstddef>
00049 #include <vector>
00050 
00051 namespace crl {
00052 namespace multisense {
00053 namespace details {
00054 namespace utility {
00055 
00056 
00057 
00058 //
00059 // The base storage class.
00060 //
00061 // To read/write from the stream, use the Reader/Writer
00062 // derivatives below.
00063 //
00064 // SENSORPOD_FIRMWARE: microblaze build, no shared() interface
00065 
00066 class BufferStream {
00067 public:
00068 
00069     void        clear ()       { m_tell = 0;                  };
00070     std::size_t tell  () const { return m_tell;               };
00071     std::size_t size  () const { return m_size;               };
00072     void       *data  () const { return m_bufferP;            };
00073     void       *peek  () const { return &(m_bufferP[m_tell]); };
00074 
00075 #ifndef SENSORPOD_FIRMWARE
00076     bool        shared() const { return m_ref.isShared();     };
00077 #endif // SENSORPOD_FIRMWARE
00078 
00079     virtual void read (void *bufferP, std::size_t length) {
00080         CRL_EXCEPTION("not implemented");
00081     };
00082     virtual void write(const void *bufferP, std::size_t length) {
00083         CRL_EXCEPTION("not implemented");
00084     };
00085 
00086     //
00087     // Move the r/w pointer in the buffer, checking bounds
00088 
00089     void seek(std::size_t idx)  {
00090 
00091         if (idx > m_size)
00092             CRL_EXCEPTION("invalid seek location %d, [0, %d] valid\n",
00093                           idx, m_size);
00094         m_tell = idx;
00095     };
00096 
00097     //
00098     // Default constructor
00099 
00100     BufferStream() :
00101         m_alloced(false),
00102         m_size(0),
00103         m_tell(0),
00104         m_bufferP(NULL) {};
00105 
00106     //
00107     // Construction, we allocate memory
00108 
00109     BufferStream(std::size_t size) :
00110         m_alloced(false),
00111         m_size(size),
00112         m_tell(0),
00113         m_bufferP(NULL) {
00114 
00115         m_bufferP = new (std::nothrow) uint8_t[size];
00116         if (NULL == m_bufferP)
00117             CRL_EXCEPTION("unable to allocate %d bytes", size);
00118         m_alloced = true;
00119     };
00120 
00121     //
00122     // Construction, memory is already allocated
00123 
00124     BufferStream(uint8_t *bufP, std::size_t size) :
00125         m_alloced(false),
00126         m_size(size),
00127         m_tell(0),
00128         m_bufferP(bufP) {};
00129 
00130     //
00131     // Destruction, free memory only if we allocated
00132 
00133     virtual ~BufferStream() {
00134 #ifdef SENSORPOD_FIRMWARE
00135         if (m_alloced)
00136 #else
00137         if (m_alloced && false == m_ref.isShared())
00138 #endif // SENSORPOD_FIRMWARE
00139             delete[] m_bufferP;
00140     };
00141 
00142     //
00143     // Copy constructor
00144 
00145     BufferStream(const BufferStream& source) {
00146         m_alloced = source.m_alloced;
00147         m_size    = source.m_size;
00148         m_tell    = 0;  // reset
00149         m_bufferP = source.m_bufferP;
00150 
00151 #ifndef SENSORPOD_FIRMWARE
00152         m_ref     = source.m_ref;
00153 #endif // SENSORPOD_FIRMWARE
00154     };
00155 
00156 protected:
00157 
00158     bool         m_alloced;
00159     std::size_t  m_size;
00160     std::size_t  m_tell;
00161     uint8_t     *m_bufferP;
00162 
00163 #ifndef SENSORPOD_FIRMWARE
00164     ReferenceCount m_ref;
00165 #endif // SENSORPOD_FIRMWARE
00166 };
00167 
00168 //
00169 // The input (deserialization) implementation. Must operate on
00170 // non-const data.
00171 
00172 class BufferStreamReader : public BufferStream {
00173 public:
00174 
00175     BufferStreamReader() : BufferStream() {};
00176     BufferStreamReader(BufferStream& s) : BufferStream(s) {};
00177     BufferStreamReader(const uint8_t *p, std::size_t s) : BufferStream(const_cast<uint8_t*>(p), s) {};
00178     BufferStreamReader(std::size_t s) : BufferStream(s) {};
00179 
00180     virtual void read (void *bufferP, std::size_t length) {
00181 
00182         if (length > (m_size - m_tell))
00183             CRL_EXCEPTION("read overflow: tell=%d, size=%d, length=%d\n",
00184                           m_tell, m_size, length);
00185 
00186         memcpy(bufferP, &(m_bufferP[m_tell]), length);
00187         m_tell += length;
00188     };
00189 
00190     template <typename T> BufferStreamReader& operator&(T &value) {
00191         this->read(&value, sizeof(T));
00192         return *this;
00193     };
00194 
00195     template <typename T> BufferStreamReader& operator&(std::vector<T>& v) {
00196         uint16_t version;
00197         uint32_t num;
00198         *this & version;
00199         *this & num;
00200         v.resize(num);
00201         for(uint32_t i=0; i<num; i++)
00202             v[i].serialize(*this, version);
00203         return *this;
00204     }
00205 
00206     BufferStreamReader& operator&(std::string& value) {
00207         uint16_t length;
00208 
00209         this->read(&length, sizeof(length));
00210         if (length > 512)
00211             CRL_EXCEPTION("unusually large string: %d bytes",
00212                                    length);
00213         else if (length > 0) {
00214             char buffer[512+1]; // length is guaranteed to be less than or equal to 512
00215             buffer[length] = '\0';
00216             this->read(buffer, length);
00217             value = std::string(buffer);
00218         }
00219         return *this;
00220     };
00221 
00222     BufferStreamReader& operator&(TimeStamp& value) {
00223         uint32_t seconds;
00224         uint32_t microseconds;
00225 
00226         this->read(&seconds, sizeof(seconds));
00227         this->read(&microseconds, sizeof(microseconds));
00228 
00229         value = seconds + 1e-6 * microseconds;
00230 
00231         return *this;
00232     };
00233 };
00234 
00235 //
00236 // The output (serialization) implementation. Able to operate
00237 // purely on const data.
00238 
00239 class BufferStreamWriter : public BufferStream {
00240 public:
00241 
00242     BufferStreamWriter() : BufferStream() {};
00243     BufferStreamWriter(BufferStream& s) : BufferStream(s) {};
00244     BufferStreamWriter(uint8_t *b, std::size_t s) : BufferStream(b, s) {};
00245     BufferStreamWriter(std::size_t s) : BufferStream(s) {};
00246 
00247     virtual void write(const void *bufferP, std::size_t length) {
00248 
00249         if ((length + m_tell) > m_size)
00250             CRL_EXCEPTION("write overflow: tell=%d, size=%d, length=%d\n",
00251                           m_tell, m_size, length);
00252 
00253         memcpy(&(m_bufferP[m_tell]), bufferP, length);
00254         m_tell += length;
00255     };
00256 
00257     template <typename T> BufferStreamWriter& operator&(const T& value) {
00258         this->write(&value, sizeof(T));
00259         return *this;
00260     };
00261 
00262     template <typename T> BufferStreamWriter& operator&(const std::vector<T>& v) {
00263         uint16_t version = T::VERSION;
00264         uint32_t num     = v.size();
00265         *this & version;
00266         *this & num;
00267         for(uint32_t i=0; i<num; i++)
00268             const_cast<T*>(&v[i])->serialize(*this, version);
00269         return *this;
00270     }
00271 
00272     BufferStreamWriter& operator&(const std::string& value) {
00273         uint16_t length = value.size();
00274 
00275         if (length > 512)
00276             CRL_EXCEPTION("unusually large string: %d bytes", length);
00277 
00278         this->write(&length, sizeof(length));
00279         if (length > 0)
00280             this->write(value.c_str(), length);
00281         return *this;
00282     };
00283 
00284     BufferStreamWriter& operator&(const TimeStamp& value) {
00285         const uint32_t seconds      = value.getSeconds();
00286         const uint32_t microseconds = value.getMicroSeconds();
00287 
00288         this->write(&seconds, sizeof(seconds));
00289         this->write(&microseconds, sizeof(microseconds));
00290 
00291         return *this;
00292     };
00293 };
00294 
00295 }}}} // namespaces
00296 
00297 #endif /* #ifndef CRL_MULTISENSE_BUFFERSTREAM_HH */


multisense_lib
Author(s):
autogenerated on Mon Oct 9 2017 03:06:21