Classes | Macros | Typedefs | Functions
mavlink_msg_small_baro.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_small_baro_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SMALL_BARO
 
#define MAVLINK_MSG_ID_183_CRC   206
 
#define MAVLINK_MSG_ID_183_LEN   12
 
#define MAVLINK_MSG_ID_SMALL_BARO   183
 
#define MAVLINK_MSG_ID_SMALL_BARO_CRC   206
 
#define MAVLINK_MSG_ID_SMALL_BARO_LEN   12
 

Typedefs

typedef struct __mavlink_small_baro_t mavlink_small_baro_t
 

Functions

static void mavlink_msg_small_baro_decode (const mavlink_message_t *msg, mavlink_small_baro_t *small_baro)
 Decode a small_baro message into a struct. More...
 
static uint16_t mavlink_msg_small_baro_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_small_baro_t *small_baro)
 Encode a small_baro struct. More...
 
static uint16_t mavlink_msg_small_baro_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_small_baro_t *small_baro)
 Encode a small_baro struct on a channel. More...
 
static float mavlink_msg_small_baro_get_altitude (const mavlink_message_t *msg)
 Send a small_baro message. More...
 
static float mavlink_msg_small_baro_get_pressure (const mavlink_message_t *msg)
 Get field pressure from small_baro message. More...
 
static float mavlink_msg_small_baro_get_temperature (const mavlink_message_t *msg)
 Get field temperature from small_baro message. More...
 
static uint16_t mavlink_msg_small_baro_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, float altitude, float pressure, float temperature)
 Pack a small_baro message. More...
 
static uint16_t mavlink_msg_small_baro_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, float altitude, float pressure, float temperature)
 Pack a small_baro message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SMALL_BARO
Value:
{ \
"SMALL_BARO", \
3, \
{ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_baro_t, altitude) }, \
{ "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_baro_t, pressure) }, \
{ "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_baro_t, temperature) }, \
} \
}
float altitude
Definition: ms4525.c:41
float pressure
Definition: ms4525.c:41
float temperature
Definition: ms4525.c:41
#define NULL
Definition: usbd_def.h:50

Definition at line 20 of file mavlink_msg_small_baro.h.

#define MAVLINK_MSG_ID_183_CRC   206

Definition at line 16 of file mavlink_msg_small_baro.h.

#define MAVLINK_MSG_ID_183_LEN   12

Definition at line 13 of file mavlink_msg_small_baro.h.

#define MAVLINK_MSG_ID_SMALL_BARO   183

Definition at line 3 of file mavlink_msg_small_baro.h.

#define MAVLINK_MSG_ID_SMALL_BARO_CRC   206

Definition at line 15 of file mavlink_msg_small_baro.h.

#define MAVLINK_MSG_ID_SMALL_BARO_LEN   12

Definition at line 12 of file mavlink_msg_small_baro.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_small_baro_decode ( const mavlink_message_t *  msg,
mavlink_small_baro_t small_baro 
)
inlinestatic

Decode a small_baro message into a struct.

Parameters
msgThe message to decode
small_baroC-struct to decode the message contents into

Definition at line 248 of file mavlink_msg_small_baro.h.

static uint16_t mavlink_msg_small_baro_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_small_baro_t small_baro 
)
inlinestatic

Encode a small_baro struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
small_baroC-struct to read the message contents from

Definition at line 115 of file mavlink_msg_small_baro.h.

static uint16_t mavlink_msg_small_baro_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_small_baro_t small_baro 
)
inlinestatic

Encode a small_baro struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
small_baroC-struct to read the message contents from

Definition at line 129 of file mavlink_msg_small_baro.h.

static float mavlink_msg_small_baro_get_altitude ( const mavlink_message_t *  msg)
inlinestatic

Send a small_baro message.

Parameters
chanMAVLink channel to send the message
altitudeCalculated Altitude (m)
pressureMeasured Differential Pressure (Pa)
temperatureMeasured Temperature (K) Get field altitude from small_baro message
Returns
Calculated Altitude (m)

Definition at line 217 of file mavlink_msg_small_baro.h.

static float mavlink_msg_small_baro_get_pressure ( const mavlink_message_t *  msg)
inlinestatic

Get field pressure from small_baro message.

Returns
Measured Differential Pressure (Pa)

Definition at line 227 of file mavlink_msg_small_baro.h.

static float mavlink_msg_small_baro_get_temperature ( const mavlink_message_t *  msg)
inlinestatic

Get field temperature from small_baro message.

Returns
Measured Temperature (K)

Definition at line 237 of file mavlink_msg_small_baro.h.

static uint16_t mavlink_msg_small_baro_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
float  altitude,
float  pressure,
float  temperature 
)
inlinestatic

Pack a small_baro message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
altitudeCalculated Altitude (m)
pressureMeasured Differential Pressure (Pa)
temperatureMeasured Temperature (K)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 41 of file mavlink_msg_small_baro.h.

static uint16_t mavlink_msg_small_baro_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
float  altitude,
float  pressure,
float  temperature 
)
inlinestatic

Pack a small_baro message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
altitudeCalculated Altitude (m)
pressureMeasured Differential Pressure (Pa)
temperatureMeasured Temperature (K)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 79 of file mavlink_msg_small_baro.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51