Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE FILT_ROT_VEL PACKING
2
 
3
#define MAVLINK_MSG_ID_FILT_ROT_VEL 184
4
 
5
typedef struct __mavlink_filt_rot_vel_t
6
{
7
 float rotVel[3]; ///< rotational velocity
8
} mavlink_filt_rot_vel_t;
9
 
10
#define MAVLINK_MSG_ID_FILT_ROT_VEL_LEN 12
11
#define MAVLINK_MSG_ID_184_LEN 12
12
 
13
#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3
14
 
15
#define MAVLINK_MESSAGE_INFO_FILT_ROT_VEL { \
16
        "FILT_ROT_VEL", \
17
        1, \
18
        {  { "rotVel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_filt_rot_vel_t, rotVel) }, \
19
         } \
20
}
21
 
22
 
23
/**
24
 * @brief Pack a filt_rot_vel message
25
 * @param system_id ID of this system
26
 * @param component_id ID of this component (e.g. 200 for IMU)
27
 * @param msg The MAVLink message to compress the data into
28
 *
29
 * @param rotVel rotational velocity
30
 * @return length of the message in bytes (excluding serial stream start sign)
31
 */
32
static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
33
                                                       const float *rotVel)
34
{
35
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
36
        char buf[12];
37
 
38
        _mav_put_float_array(buf, 0, rotVel, 3);
39
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
40
#else
41
        mavlink_filt_rot_vel_t packet;
42
 
43
        mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3);
44
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
45
#endif
46
 
47
        msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
48
        return mavlink_finalize_message(msg, system_id, component_id, 12, 79);
49
}
50
 
51
/**
52
 * @brief Pack a filt_rot_vel message on a channel
53
 * @param system_id ID of this system
54
 * @param component_id ID of this component (e.g. 200 for IMU)
55
 * @param chan The MAVLink channel this message was sent over
56
 * @param msg The MAVLink message to compress the data into
57
 * @param rotVel rotational velocity
58
 * @return length of the message in bytes (excluding serial stream start sign)
59
 */
60
static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
61
                                                           mavlink_message_t* msg,
62
                                                           const float *rotVel)
63
{
64
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
65
        char buf[12];
66
 
67
        _mav_put_float_array(buf, 0, rotVel, 3);
68
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
69
#else
70
        mavlink_filt_rot_vel_t packet;
71
 
72
        mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3);
73
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
74
#endif
75
 
76
        msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
77
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 79);
78
}
79
 
80
/**
81
 * @brief Encode a filt_rot_vel struct into a message
82
 *
83
 * @param system_id ID of this system
84
 * @param component_id ID of this component (e.g. 200 for IMU)
85
 * @param msg The MAVLink message to compress the data into
86
 * @param filt_rot_vel C-struct to read the message contents from
87
 */
88
static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel)
89
{
90
        return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel);
91
}
92
 
93
/**
94
 * @brief Send a filt_rot_vel message
95
 * @param chan MAVLink channel to send the message
96
 *
97
 * @param rotVel rotational velocity
98
 */
99
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
100
 
101
static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float *rotVel)
102
{
103
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
104
        char buf[12];
105
 
106
        _mav_put_float_array(buf, 0, rotVel, 3);
107
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, 12, 79);
108
#else
109
        mavlink_filt_rot_vel_t packet;
110
 
111
        mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3);
112
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, 12, 79);
113
#endif
114
}
115
 
116
#endif
117
 
118
// MESSAGE FILT_ROT_VEL UNPACKING
119
 
120
 
121
/**
122
 * @brief Get field rotVel from filt_rot_vel message
123
 *
124
 * @return rotational velocity
125
 */
126
static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float *rotVel)
127
{
128
        return _MAV_RETURN_float_array(msg, rotVel, 3,  0);
129
}
130
 
131
/**
132
 * @brief Decode a filt_rot_vel message into a struct
133
 *
134
 * @param msg The message to decode
135
 * @param filt_rot_vel C-struct to decode the message contents into
136
 */
137
static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, mavlink_filt_rot_vel_t* filt_rot_vel)
138
{
139
#if MAVLINK_NEED_BYTE_SWAP
140
        mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel);
141
#else
142
        memcpy(filt_rot_vel, _MAV_PAYLOAD(msg), 12);
143
#endif
144
}