Go to the source code of this file.
Classes | |
struct | __mavlink_vibration_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_VIBRATION |
#define | MAVLINK_MSG_ID_241_CRC 90 |
#define | MAVLINK_MSG_ID_241_LEN 32 |
#define | MAVLINK_MSG_ID_VIBRATION 241 |
#define | MAVLINK_MSG_ID_VIBRATION_CRC 90 |
#define | MAVLINK_MSG_ID_VIBRATION_LEN 32 |
Typedefs | |
typedef struct __mavlink_vibration_t | mavlink_vibration_t |
Functions | |
static void | mavlink_msg_vibration_decode (const mavlink_message_t *msg, mavlink_vibration_t *vibration) |
Decode a vibration message into a struct. More... | |
static uint16_t | mavlink_msg_vibration_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_vibration_t *vibration) |
Encode a vibration struct. More... | |
static uint16_t | mavlink_msg_vibration_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_vibration_t *vibration) |
Encode a vibration struct on a channel. More... | |
static uint32_t | mavlink_msg_vibration_get_clipping_0 (const mavlink_message_t *msg) |
Get field clipping_0 from vibration message. More... | |
static uint32_t | mavlink_msg_vibration_get_clipping_1 (const mavlink_message_t *msg) |
Get field clipping_1 from vibration message. More... | |
static uint32_t | mavlink_msg_vibration_get_clipping_2 (const mavlink_message_t *msg) |
Get field clipping_2 from vibration message. More... | |
static uint64_t | mavlink_msg_vibration_get_time_usec (const mavlink_message_t *msg) |
Send a vibration message. More... | |
static float | mavlink_msg_vibration_get_vibration_x (const mavlink_message_t *msg) |
Get field vibration_x from vibration message. More... | |
static float | mavlink_msg_vibration_get_vibration_y (const mavlink_message_t *msg) |
Get field vibration_y from vibration message. More... | |
static float | mavlink_msg_vibration_get_vibration_z (const mavlink_message_t *msg) |
Get field vibration_z from vibration message. More... | |
static uint16_t | mavlink_msg_vibration_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) |
Pack a vibration message. More... | |
static uint16_t | mavlink_msg_vibration_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) |
Pack a vibration message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_VIBRATION |
Definition at line 24 of file mavlink_msg_vibration.h.
#define MAVLINK_MSG_ID_241_CRC 90 |
Definition at line 20 of file mavlink_msg_vibration.h.
#define MAVLINK_MSG_ID_241_LEN 32 |
Definition at line 17 of file mavlink_msg_vibration.h.
#define MAVLINK_MSG_ID_VIBRATION 241 |
Definition at line 3 of file mavlink_msg_vibration.h.
#define MAVLINK_MSG_ID_VIBRATION_CRC 90 |
Definition at line 19 of file mavlink_msg_vibration.h.
#define MAVLINK_MSG_ID_VIBRATION_LEN 32 |
Definition at line 16 of file mavlink_msg_vibration.h.
typedef struct __mavlink_vibration_t mavlink_vibration_t |
|
inlinestatic |
Decode a vibration message into a struct.
msg | The message to decode |
vibration | C-struct to decode the message contents into |
Definition at line 340 of file mavlink_msg_vibration.h.
|
inlinestatic |
Encode a vibration struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
vibration | C-struct to read the message contents from |
Definition at line 147 of file mavlink_msg_vibration.h.
|
inlinestatic |
Encode a vibration struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
vibration | C-struct to read the message contents from |
Definition at line 161 of file mavlink_msg_vibration.h.
|
inlinestatic |
Get field clipping_0 from vibration message.
Definition at line 309 of file mavlink_msg_vibration.h.
|
inlinestatic |
Get field clipping_1 from vibration message.
Definition at line 319 of file mavlink_msg_vibration.h.
|
inlinestatic |
Get field clipping_2 from vibration message.
Definition at line 329 of file mavlink_msg_vibration.h.
|
inlinestatic |
Send a vibration message.
chan | MAVLink channel to send the message |
time_usec | Timestamp (micros since boot or Unix epoch) |
vibration_x | Vibration levels on X-axis |
vibration_y | Vibration levels on Y-axis |
vibration_z | Vibration levels on Z-axis |
clipping_0 | first accelerometer clipping count |
clipping_1 | second accelerometer clipping count |
clipping_2 | third accelerometer clipping count Get field time_usec from vibration message |
Definition at line 269 of file mavlink_msg_vibration.h.
|
inlinestatic |
Get field vibration_x from vibration message.
Definition at line 279 of file mavlink_msg_vibration.h.
|
inlinestatic |
Get field vibration_y from vibration message.
Definition at line 289 of file mavlink_msg_vibration.h.
|
inlinestatic |
Get field vibration_z from vibration message.
Definition at line 299 of file mavlink_msg_vibration.h.
|
inlinestatic |
Pack a vibration message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
time_usec | Timestamp (micros since boot or Unix epoch) |
vibration_x | Vibration levels on X-axis |
vibration_y | Vibration levels on Y-axis |
vibration_z | Vibration levels on Z-axis |
clipping_0 | first accelerometer clipping count |
clipping_1 | second accelerometer clipping count |
clipping_2 | third accelerometer clipping count |
Definition at line 53 of file mavlink_msg_vibration.h.
|
inlinestatic |
Pack a vibration message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
time_usec | Timestamp (micros since boot or Unix epoch) |
vibration_x | Vibration levels on X-axis |
vibration_y | Vibration levels on Y-axis |
vibration_z | Vibration levels on Z-axis |
clipping_0 | first accelerometer clipping count |
clipping_1 | second accelerometer clipping count |
clipping_2 | third accelerometer clipping count |
Definition at line 103 of file mavlink_msg_vibration.h.