message.hpp
Go to the documentation of this file.
1 
2 #pragma once
3 
4 #include <array>
5 #include <cassert>
6 #include <cstring>
7 #include <sstream>
8 #include <string>
9 #include <iostream>
10 
11 #ifndef MAVLINK_HELPER
12 #define MAVLINK_HELPER static inline
13 #endif
14 
15 #define MAVLINK_USE_CXX_NAMESPACE // put C-lib into namespace
16 #include "mavlink_types.h"
17 
18 #define _MAVLINK_CONVERSIONS_H_ // do not include mavlink_conversions.h
19 #define MAVLINK_GET_MSG_ENTRY // user should provide mavlink_get_msg_entry()
20 namespace mavlink {
30 const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid);
31 } // namespace mavlink
32 
33 #include "mavlink_helpers.h"
34 
35 #include "msgmap.hpp"
36 
37 namespace mavlink {
38 
40 using msgid_t = uint32_t;
41 
45 struct Message {
46  static constexpr msgid_t MSG_ID = UINT32_MAX;
47  static constexpr size_t LENGTH = 0;
48  static constexpr size_t MIN_LENGTH = 0;
49  static constexpr uint8_t CRC_EXTRA = 0;
50  static constexpr auto NAME = "BASE";
51 
52  struct Info {
54  size_t length;
55  size_t min_length;
56  uint8_t crc_extra;
57  };
58 
62  virtual std::string get_name(void) const = 0;
63 
67  virtual Info get_message_info(void) const = 0;
68 
72  virtual std::string to_yaml(void) const = 0;
73 
79  virtual void serialize(MsgMap &map) const = 0;
80 
86  virtual void deserialize(MsgMap &msp) = 0;
87 };
88 
94 template<size_t _N>
95 std::string to_string(const std::array<char, _N> &a)
96 {
97  return std::string(a.data(), strnlen(a.data(), a.size()));
98 }
99 
103 template<typename _T, size_t _N>
104 std::string to_string(const std::array<_T, _N> &a)
105 {
106  std::stringstream ss;
107  bool first = true;
108 
109  for (auto const &v : a) {
110  if (first) {
111  first = false;
112  } else {
113  ss << ", ";
114  }
115 
116  // +v treated as 0+v, it's safe for all types,
117  // but force int8_t/uint8_t to be print as number.
118  ss << +v;
119  }
120 
121  return ss.str();
122 }
123 
130 template<size_t _N>
131 void set_string(std::array<char, _N> &a, const std::string &s)
132 {
133  strncpy(a.data(), s.c_str(), a.size());
134 }
135 
142 template<size_t _N>
143 void set_string_z(std::array<char, _N> &a, const std::string &s)
144 {
145  strncpy(a.data(), s.c_str(), a.size() - 1);
146  a[a.size() - 1] = '\0';
147 }
148 
149 } // namespace mavlink


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02