11 #ifndef MAVLINK_HELPER 12 #define MAVLINK_HELPER static inline 15 #define MAVLINK_USE_CXX_NAMESPACE // put C-lib into namespace 16 #include "mavlink_types.h" 18 #define _MAVLINK_CONVERSIONS_H_ // do not include mavlink_conversions.h 19 #define MAVLINK_GET_MSG_ENTRY // user should provide mavlink_get_msg_entry() 33 #include "mavlink_helpers.h" 50 static constexpr
auto NAME =
"BASE";
62 virtual std::string
get_name(
void)
const = 0;
72 virtual std::string
to_yaml(
void)
const = 0;
95 std::string
to_string(
const std::array<char, _N> &a)
97 return std::string(a.data(), strnlen(a.data(), a.size()));
103 template<
typename _T,
size_t _N>
106 std::stringstream ss;
109 for (
auto const &v : a) {
133 strncpy(a.data(), s.c_str(), a.size());
145 strncpy(a.data(), s.c_str(), a.size() - 1);
146 a[a.size() - 1] =
'\0';
static constexpr auto NAME
static constexpr size_t MIN_LENGTH
const mavlink_msg_entry_t * mavlink_get_msg_entry(uint32_t msgid)
static constexpr uint8_t CRC_EXTRA
virtual void serialize(MsgMap &map) const =0
virtual Info get_message_info(void) const =0
virtual std::string to_yaml(void) const =0
void set_string_z(std::array< char, _N > &a, const std::string &s)
uint32_t msgid_t
Message ID type.
static constexpr msgid_t MSG_ID
void set_string(std::array< char, _N > &a, const std::string &s)
virtual void deserialize(MsgMap &msp)=0
static constexpr size_t LENGTH
std::string to_string(const std::array< char, _N > &a)
virtual std::string get_name(void) const =0