msgbuffer.h
Go to the documentation of this file.
1 
23 #pragma once
24 
25 #include <cassert>
26 #include "mavlink/v2.0/common/mavlink.h"
27 
28 namespace gazebo {
32 struct MsgBuffer {
34  static constexpr ssize_t MAX_SIZE = MAVLINK_MAX_PACKET_LEN + 16;
35  uint8_t data[MAX_SIZE];
36  ssize_t len;
37  ssize_t pos;
38 
40  pos(0),
41  len(0)
42  { }
43 
47  explicit MsgBuffer(const mavlink_message_t *msg) :
48  pos(0)
49  {
50  len = mavlink_msg_to_send_buffer(data, msg);
51  // paranoic check, it must be less than MAVLINK_MAX_PACKET_LEN
52  assert(len < MAX_SIZE);
53  }
54 
59  MsgBuffer(const uint8_t *bytes, ssize_t nbytes) :
60  pos(0),
61  len(nbytes)
62  {
63  assert(0 < nbytes && nbytes < MAX_SIZE);
64  memcpy(data, bytes, nbytes);
65  }
66 
67  virtual ~MsgBuffer() {
68  pos = 0;
69  len = 0;
70  }
71 
72  uint8_t *dpos() {
73  return data + pos;
74  }
75 
76  ssize_t nbytes() {
77  return len - pos;
78  }
79 };
80 } // namespace gazebo
MsgBuffer(const mavlink_message_t *msg)
Buffer constructor from mavlink_message_t.
Definition: msgbuffer.h:47
static constexpr ssize_t MAX_SIZE
Maximum buffer size with padding for CRC bytes (280 + padding)
Definition: msgbuffer.h:34
ssize_t nbytes()
Definition: msgbuffer.h:76
Message buffer for internal use in libmavconn.
Definition: msgbuffer.h:32
MsgBuffer(const uint8_t *bytes, ssize_t nbytes)
Buffer constructor for send_bytes()
Definition: msgbuffer.h:59
virtual ~MsgBuffer()
Definition: msgbuffer.h:67
uint8_t * dpos()
Definition: msgbuffer.h:72
uint8_t data[MAX_SIZE]
Definition: msgbuffer.h:35


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04