Public Member Functions | Private Member Functions | Private Attributes | List of all members
mavlink::MsgMap Class Reference

#include <msgmap.hpp>

Public Member Functions

 MsgMap (mavlink_message_t *p)
 
 MsgMap (mavlink_message_t &p)
 
 MsgMap (const mavlink_message_t *p)
 
template<typename _T >
void operator<< (const _T data)
 
template<class _T , size_t _Size>
void operator<< (const std::array< _T, _Size > &data)
 
template<typename _T >
void operator>> (_T &data)
 
template<class _T , size_t _Size>
void operator>> (std::array< _T, _Size > &data)
 
void reset ()
 
void reset (uint32_t msgid, uint8_t len)
 

Private Member Functions

template<typename _T , typename _Tout >
void cmsg_memcpy_bzero_swap_set_data (_T &buf, _Tout &data)
 
template<typename _T , typename _Tin >
void msg_swap_memcpy (_T &buf, _Tin data)
 

Private Attributes

const mavlink_message_tcmsg
 
mavlink_message_tmsg
 
size_t pos
 

Detailed Description

Serialization helper wrapper for mavlink_message_t

Definition at line 12 of file msgmap.hpp.

Constructor & Destructor Documentation

mavlink::MsgMap::MsgMap ( mavlink_message_t p)
inlineexplicit

Definition at line 15 of file msgmap.hpp.

mavlink::MsgMap::MsgMap ( mavlink_message_t p)
inlineexplicit

Definition at line 19 of file msgmap.hpp.

mavlink::MsgMap::MsgMap ( const mavlink_message_t p)
inlineexplicit

Definition at line 23 of file msgmap.hpp.

Member Function Documentation

template<typename _T , typename _Tout >
void mavlink::MsgMap::cmsg_memcpy_bzero_swap_set_data ( _T &  buf,
_Tout &  data 
)
inlineprivate

Definition at line 144 of file msgmap.hpp.

template<typename _T , typename _Tin >
void mavlink::MsgMap::msg_swap_memcpy ( _T &  buf,
_Tin  data 
)
inlineprivate

Definition at line 70 of file msgmap.hpp.

template<typename _T >
void mavlink::MsgMap::operator<< ( const _T  data)

Definition at line 101 of file msgmap.hpp.

template<class _T , size_t _Size>
void mavlink::MsgMap::operator<< ( const std::array< _T, _Size > &  data)

Definition at line 136 of file msgmap.hpp.

template<typename _T >
void mavlink::MsgMap::operator>> ( _T &  data)

Definition at line 192 of file msgmap.hpp.

template<class _T , size_t _Size>
void mavlink::MsgMap::operator>> ( std::array< _T, _Size > &  data)

Definition at line 234 of file msgmap.hpp.

void mavlink::MsgMap::reset ( )
inline

Definition at line 27 of file msgmap.hpp.

void mavlink::MsgMap::reset ( uint32_t  msgid,
uint8_t  len 
)
inline

Definition at line 32 of file msgmap.hpp.

Member Data Documentation

const mavlink_message_t* mavlink::MsgMap::cmsg
private

Definition at line 55 of file msgmap.hpp.

mavlink_message_t* mavlink::MsgMap::msg
private

Definition at line 54 of file msgmap.hpp.

size_t mavlink::MsgMap::pos
private

Definition at line 56 of file msgmap.hpp.


The documentation for this class was generated from the following file:


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