serialization.h
Go to the documentation of this file.
1 //==============================================================================
2 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //==============================================================================
28 
29 #ifndef UBLOX_SERIALIZATION_H
30 #define UBLOX_SERIALIZATION_H
31 
32 #include <ros/console.h>
33 #include <stdint.h>
34 #include <boost/call_traits.hpp>
35 #include <vector>
36 #include <algorithm>
37 
38 #include "checksum.h"
39 
48 
49 
54 namespace ublox {
55 
57 static const uint8_t DEFAULT_SYNC_A = 0xB5;
59 static const uint8_t DEFAULT_SYNC_B = 0x62;
61 static const uint8_t kHeaderLength = 6;
63 static const uint8_t kChecksumLength = 2;
64 
68 template <typename T>
69 struct Serializer {
76  static void read(const uint8_t *data, uint32_t count,
77  typename boost::call_traits<T>::reference message);
85  static uint32_t serializedLength(
86  typename boost::call_traits<T>::param_type message);
87 
94  static void write(uint8_t *data, uint32_t size,
95  typename boost::call_traits<T>::param_type message);
96 };
97 
102 template <typename T>
103 class Message {
104  public:
111  static bool canDecode(uint8_t class_id, uint8_t message_id) {
112  return std::find(keys_.begin(), keys_.end(),
113  std::make_pair(class_id, message_id)) != keys_.end();
114  }
115 
122  static void addKey(uint8_t class_id, uint8_t message_id) {
123  keys_.push_back(std::make_pair(class_id, message_id));
124  }
125 
127  {
128  StaticKeyInitializer(uint8_t class_id, uint8_t message_id) {
129  Message<T>::addKey(class_id, message_id);
130  }
131  };
132 
133  private:
134  static std::vector<std::pair<uint8_t,uint8_t> > keys_;
135 };
136 
140 struct Options {
144  Options() : sync_a(DEFAULT_SYNC_A), sync_b(DEFAULT_SYNC_B),
145  header_length(kHeaderLength), checksum_length(kChecksumLength) {}
147  uint8_t sync_a;
149  uint8_t sync_b;
151  uint8_t header_length;
153  uint8_t checksum_length;
154 
160  return header_length + checksum_length;
161  }
162 };
163 
167 class Reader {
168  public:
175  Reader(const uint8_t *data, uint32_t count,
176  const Options &options = Options()) :
177  data_(data), count_(count), found_(false), options_(options) {}
178 
179  typedef const uint8_t *iterator;
180 
185  iterator search()
186  {
187  if (found_) next();
188 
189  // Search for a message header
190  for( ; count_ > 0; --count_, ++data_) {
191  if (data_[0] == options_.sync_a &&
192  (count_ == 1 || data_[1] == options_.sync_b))
193  break;
194  }
195 
196  return data_;
197  }
198 
203  bool found()
204  {
205  if (found_) return true;
206  // Verify message is long enough to have sync chars, id, length & checksum
207  if (count_ < options_.wrapper_length()) return false;
208  // Verify the header bits
209  if (data_[0] != options_.sync_a || data_[1] != options_.sync_b)
210  return false;
211  // Verify that the buffer length is long enough based on the received
212  // message length
213  if (count_ < length() + options_.wrapper_length()) return false;
214 
215  found_ = true;
216  return true;
217  }
218 
226  iterator next() {
227  if (found()) {
228  uint32_t size = length() + options_.wrapper_length();
229  data_ += size; count_ -= size;
230  }
231  found_ = false;
232  return data_;
233  }
234 
239  iterator pos() {
240  return data_;
241  }
242 
243  iterator end() {
244  return data_ + count_;
245  }
246 
247  uint8_t classId() { return data_[2]; }
248  uint8_t messageId() { return data_[3]; }
249 
257  uint32_t length() { return (data_[5] << 8) + data_[4]; }
258  const uint8_t *data() { return data_ + options_.header_length; }
259 
265  uint16_t checksum() {
266  return *reinterpret_cast<const uint16_t *>(data_ + options_.header_length +
267  length());
268  }
269 
275  template <typename T>
276  bool read(typename boost::call_traits<T>::reference message,
277  bool search = false) {
278  if (search) this->search();
279  if (!found()) return false;
280  if (!Message<T>::canDecode(classId(), messageId())) return false;
281 
282  uint16_t chk;
283  if (calculateChecksum(data_ + 2, length() + 4, chk) != this->checksum()) {
284  // checksum error
285  ROS_DEBUG("U-Blox read checksum error: 0x%02x / 0x%02x", classId(),
286  messageId());
287  return false;
288  }
289 
290  Serializer<T>::read(data_ + options_.header_length, length(), message);
291  return true;
292  }
293 
299  template <typename T>
300  bool hasType() {
301  if (!found()) return false;
302  return Message<T>::canDecode(classId(), messageId());
303  }
304 
310  bool isMessage(uint8_t class_id, uint8_t message_id) {
311  if (!found()) return false;
312  return (classId() == class_id && messageId() == message_id);
313  }
314 
315  private:
317  const uint8_t *data_;
319  uint32_t count_;
321  bool found_;
324 };
325 
329 class Writer {
330  public:
331  typedef uint8_t *iterator;
332 
339  Writer(uint8_t *data, uint32_t size, const Options &options = Options()) :
340  data_(data), size_(size), options_(options) {}
341 
349  template <typename T> bool write(const T& message,
350  uint8_t class_id = T::CLASS_ID,
351  uint8_t message_id = T::MESSAGE_ID) {
352  // Check for buffer overflow
353  uint32_t length = Serializer<T>::serializedLength(message);
354  if (size_ < length + options_.wrapper_length()) {
355  ROS_ERROR("u-blox write buffer overflow. Message %u / %u not written",
356  class_id, message_id);
357  return false;
358  }
359  // Encode the message and add it to the buffer
360  Serializer<T>::write(data_ + options_.header_length,
361  size_ - options_.header_length, message);
362  return write(0, length, class_id, message_id);
363  }
364 
374  bool write(const uint8_t* message, uint32_t length, uint8_t class_id,
375  uint8_t message_id) {
376  if (size_ < length + options_.wrapper_length()) {
377  ROS_ERROR("u-blox write buffer overflow. Message %u / %u not written",
378  class_id, message_id);
379  return false;
380  }
381  iterator start = data_;
382 
383  // write header
384  *data_++ = options_.sync_a;
385  *data_++ = options_.sync_b;
386  *data_++ = class_id;
387  *data_++ = message_id;
388  *data_++ = length & 0xFF;
389  *data_++ = (length >> 8) & 0xFF;
390  size_ -= options_.header_length;
391 
392  // write message
393  if (message) std::copy(message, message + length, data_);
394  data_ += length;
395  size_ -= length;
396 
397  // write checksum
398  uint8_t ck_a, ck_b;
399  calculateChecksum(start + 2, length + 4, ck_a, ck_b);
400  *data_++ = ck_a;
401  *data_++ = ck_b;
402  size_ -= options_.checksum_length;
403 
404  return true;
405  }
406 
407  iterator end() {
408  return data_;
409  }
410 
411  private:
413  iterator data_;
415 
416  uint32_t size_;
419 };
420 
421 } // namespace ublox
422 
423 // Use to declare u-blox messages and message serializers
424 #define DECLARE_UBLOX_MESSAGE(class_id, message_id, package, message) \
425  template class ublox::Serializer<package::message>; \
426  template class ublox::Message<package::message>; \
427  namespace package { namespace { \
428  static const ublox::Message<message>::StaticKeyInitializer static_key_initializer_##message(class_id, message_id); \
429  } } \
430 
431 // Use for messages which have the same structure but different IDs, e.g. INF
432 // Call DECLARE_UBLOX_MESSAGE for the first message and DECLARE_UBLOX_MESSAGE_ID
433 // for following declarations
434 #define DECLARE_UBLOX_MESSAGE_ID(class_id, message_id, package, message, name) \
435  namespace package { namespace { \
436  static const ublox::Message<message>::StaticKeyInitializer static_key_initializer_##name(class_id, message_id); \
437  } } \
438 
439 
440 // use implementation of class Serializer in "serialization_ros.h"
441 #include "serialization_ros.h"
442 
443 #endif // UBLOX_SERIALIZATION_H
uint8_t classId()
uint8_t sync_a
The sync_a byte value identifying the start of a message.
bool isMessage(uint8_t class_id, uint8_t message_id)
Does the u-blox message have the given class and message ID?
static const uint8_t DEFAULT_SYNC_A
u-blox message Sync A char
Definition: serialization.h:57
iterator end()
iterator search()
Search the buffer for the beginning of the next u-blox message.
ROSCPP_DECL void start()
Options options_
Options representing the sync char values, etc.
uint32_t length()
Get the length of the u-blox message payload.
static void write(uint8_t *data, uint32_t size, typename boost::call_traits< T >::param_type message)
Encode the message payload as a byte array.
int wrapper_length()
Get the number of bytes in the header and footer.
StaticKeyInitializer(uint8_t class_id, uint8_t message_id)
static void calculateChecksum(const uint8_t *data, uint32_t size, uint8_t &ck_a, uint8_t &ck_b)
calculate the checksum of a u-blox_message
Definition: checksum.h:43
bool write(const T &message, uint8_t class_id=T::CLASS_ID, uint8_t message_id=T::MESSAGE_ID)
Encode the u-blox message.
iterator end()
uint16_t checksum()
Get the checksum of the u-blox message.
static bool canDecode(uint8_t class_id, uint8_t message_id)
Can this message type decode a u-blox message with the given ID?
iterator data_
The buffer of message bytes.
const uint8_t * data_
The buffer of message bytes.
Options for the Reader and Writer for encoding and decoding messages.
static std::vector< std::pair< uint8_t, uint8_t > > keys_
Encodes a u-blox ROS message as a byte array.
static void read(const uint8_t *data, uint32_t count, typename boost::call_traits< T >::reference message)
Decode the message payload from the data buffer.
Options options_
Options representing the sync char values, etc.
Writer(uint8_t *data, uint32_t size, const Options &options=Options())
Construct a Writer with the given buffer.
uint32_t count_
the number of bytes in the buffer, //! decrement as the buffer is read
uint32_t size_
The number of remaining bytes in the buffer.
uint8_t sync_b
The sync_b byte value identifying the start of a message.
iterator next()
Go to the start of the next message based on the received message length.
Decodes byte messages into u-blox ROS messages.
static uint32_t serializedLength(typename boost::call_traits< T >::param_type message)
Get the length of the message payload in bytes.
bool hasType()
Can the given message type decode the current message in the buffer?
static void addKey(uint8_t class_id, uint8_t message_id)
Indicate that this message type can decode u-blox messages with the given ID.
static const uint8_t kHeaderLength
Number of bytes in a message header (Sync chars + class ID + message ID)
Definition: serialization.h:61
const uint8_t * data()
bool found()
Has a u-blox message been found in the buffer?
static const uint8_t kChecksumLength
Number of checksum bytes in the u-blox message.
Definition: serialization.h:63
iterator pos()
Get the current position in the read buffer.
Reader(const uint8_t *data, uint32_t count, const Options &options=Options())
uint8_t messageId()
uint8_t * iterator
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
uint8_t header_length
The length of the message header in bytes (everything before the payload)
static const uint8_t DEFAULT_SYNC_B
u-blox message Sync B char
Definition: serialization.h:59
bool found_
Whether or not a message has been found.
const uint8_t * iterator
#define ROS_ERROR(...)
uint8_t checksum_length
The length of the checksum in bytes.
bool read(typename boost::call_traits< T >::reference message, bool search=false)
Decode the given message.
bool write(const uint8_t *message, uint32_t length, uint8_t class_id, uint8_t message_id)
Wrap the encoded message payload with a header and checksum and add it to the buffer.
Keeps track of which class and message IDs can be decoded by a given message type.
Definition: checksum.h:34
Encodes and decodes messages.
Definition: serialization.h:69
#define ROS_DEBUG(...)


ublox_serialization
Author(s): Johannes Meyer
autogenerated on Thu Jan 28 2021 03:13:50