Classes | Defines | Functions
mavlink_helpers.h File Reference
#include "string.h"
#include "checksum.h"
#include "mavlink_types.h"
Include dependency graph for include_v0.9/mavlink_helpers.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

union  __mavlink_bitfield

Defines

#define MAVLINK_HELPER

Functions

MAVLINK_HELPER uint16_t mavlink_finalize_message (mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
 Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan (mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
 Finalize a MAVLink message with channel assignment.
MAVLINK_HELPER mavlink_message_tmavlink_get_channel_buffer (uint8_t chan)
MAVLINK_HELPER mavlink_status_tmavlink_get_channel_status (uint8_t chan)
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer (uint8_t *buffer, const mavlink_message_t *msg)
 Pack a message to send it over a serial byte stream.
MAVLINK_HELPER uint8_t mavlink_parse_char (uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status)
MAVLINK_HELPER void mavlink_start_checksum (mavlink_message_t *msg)
MAVLINK_HELPER void mavlink_update_checksum (mavlink_message_t *msg, uint8_t c)
MAVLINK_HELPER uint8_t put_bitfield_n_by_index (int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t *r_bit_index, uint8_t *buffer)
 Put a bitfield of length 1-32 bit into the buffer.

Define Documentation

#define MAVLINK_HELPER

Definition at line 9 of file include_v0.9/mavlink_helpers.h.


Function Documentation

MAVLINK_HELPER uint16_t mavlink_finalize_message ( mavlink_message_t msg,
uint8_t  system_id,
uint8_t  component_id,
uint8_t  length 
)

Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.

Definition at line 89 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER uint16_t mavlink_finalize_message_chan ( mavlink_message_t msg,
uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
uint8_t  length 
)

Finalize a MAVLink message with channel assignment.

This function calculates the checksum and sets length and aircraft id correctly. It assumes that the message id and the payload are already correctly set. This function can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.

Parameters:
msgMessage to finalize
system_idId of the sending (this) system, 1-127
lengthMessage length

Definition at line 55 of file include_v0.9/mavlink_helpers.h.

Definition at line 24 of file include_v0.9/mavlink_helpers.h.

Definition at line 15 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer ( uint8_t *  buffer,
const mavlink_message_t msg 
)

Pack a message to send it over a serial byte stream.

Definition at line 157 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER uint8_t mavlink_parse_char ( uint8_t  chan,
uint8_t  c,
mavlink_message_t r_message,
mavlink_status_t r_mavlink_status 
)

This is a convenience function which handles the complete MAVLink parsing. the function will parse one byte at a time and return the complete packet once it could be successfully decoded. Checksum and other failures will be silently ignored.

Parameters:
chanID of the current channel. This allows to parse different channels with this function. a channel is not a physical message channel like a serial port, but a logic partition of the communication streams in this case. COMM_NB is the limit for the number of channels on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
cThe char to barse
returnMsgNULL if no message could be decoded, the message data else
Returns:
0 if no message could be decoded, 1 else

A typical use scenario of this function call is:

 #include <inttypes.h> // For fixed-width uint8_t type

 mavlink_message_t msg;
 int chan = 0;


 while(serial.bytesAvailable > 0)
 {
   uint8_t byte = serial.getNextByte();
   if (mavlink_parse_char(chan, byte, &msg))
     {
     printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
     }
 }

< The currently decoded message

< The current decode status

Definition at line 219 of file include_v0.9/mavlink_helpers.h.

Definition at line 173 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER void mavlink_update_checksum ( mavlink_message_t msg,
uint8_t  c 
)

Definition at line 178 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER uint8_t put_bitfield_n_by_index ( int32_t  b,
uint8_t  bits,
uint8_t  packet_index,
uint8_t  bit_index,
uint8_t *  r_bit_index,
uint8_t *  buffer 
)

Put a bitfield of length 1-32 bit into the buffer.

Parameters:
bthe value to add, will be encoded in the bitfield
bitsnumber of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
packet_indexthe position in the packet (the index of the first byte to use)
bit_indexthe position in the byte (the index of the first bit to use)
bufferpacket buffer to write into
Returns:
new position of the last used byte in the buffer

Definition at line 420 of file include_v0.9/mavlink_helpers.h.



mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57