Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE SCALED_PRESSURE PACKING
2
 
3
#define MAVLINK_MSG_ID_SCALED_PRESSURE 38
4
 
5
typedef struct __mavlink_scaled_pressure_t
6
{
7
 uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
8
 float press_abs; ///< Absolute pressure (hectopascal)
9
 float press_diff; ///< Differential pressure 1 (hectopascal)
10
 int16_t temperature; ///< Temperature measurement (0.01 degrees celsius)
11
} mavlink_scaled_pressure_t;
12
 
13
#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 18
14
#define MAVLINK_MSG_ID_38_LEN 18
15
 
16
 
17
 
18
#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
19
        "SCALED_PRESSURE", \
20
        4, \
21
        {  { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_pressure_t, usec) }, \
22
         { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
23
         { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
24
         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_pressure_t, temperature) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a scaled_pressure message
31
 * @param system_id ID of this system
32
 * @param component_id ID of this component (e.g. 200 for IMU)
33
 * @param msg The MAVLink message to compress the data into
34
 *
35
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
36
 * @param press_abs Absolute pressure (hectopascal)
37
 * @param press_diff Differential pressure 1 (hectopascal)
38
 * @param temperature Temperature measurement (0.01 degrees celsius)
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint64_t usec, float press_abs, float press_diff, int16_t temperature)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[18];
46
        _mav_put_uint64_t(buf, 0, usec);
47
        _mav_put_float(buf, 8, press_abs);
48
        _mav_put_float(buf, 12, press_diff);
49
        _mav_put_int16_t(buf, 16, temperature);
50
 
51
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
52
#else
53
        mavlink_scaled_pressure_t packet;
54
        packet.usec = usec;
55
        packet.press_abs = press_abs;
56
        packet.press_diff = press_diff;
57
        packet.temperature = temperature;
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
60
#endif
61
 
62
        msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
63
        return mavlink_finalize_message(msg, system_id, component_id, 18);
64
}
65
 
66
/**
67
 * @brief Pack a scaled_pressure message on a channel
68
 * @param system_id ID of this system
69
 * @param component_id ID of this component (e.g. 200 for IMU)
70
 * @param chan The MAVLink channel this message was sent over
71
 * @param msg The MAVLink message to compress the data into
72
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
73
 * @param press_abs Absolute pressure (hectopascal)
74
 * @param press_diff Differential pressure 1 (hectopascal)
75
 * @param temperature Temperature measurement (0.01 degrees celsius)
76
 * @return length of the message in bytes (excluding serial stream start sign)
77
 */
78
static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
79
                                                           mavlink_message_t* msg,
80
                                                           uint64_t usec,float press_abs,float press_diff,int16_t temperature)
81
{
82
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83
        char buf[18];
84
        _mav_put_uint64_t(buf, 0, usec);
85
        _mav_put_float(buf, 8, press_abs);
86
        _mav_put_float(buf, 12, press_diff);
87
        _mav_put_int16_t(buf, 16, temperature);
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
90
#else
91
        mavlink_scaled_pressure_t packet;
92
        packet.usec = usec;
93
        packet.press_abs = press_abs;
94
        packet.press_diff = press_diff;
95
        packet.temperature = temperature;
96
 
97
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
98
#endif
99
 
100
        msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
101
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
102
}
103
 
104
/**
105
 * @brief Encode a scaled_pressure struct into a message
106
 *
107
 * @param system_id ID of this system
108
 * @param component_id ID of this component (e.g. 200 for IMU)
109
 * @param msg The MAVLink message to compress the data into
110
 * @param scaled_pressure C-struct to read the message contents from
111
 */
112
static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
113
{
114
        return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->usec, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
115
}
116
 
117
/**
118
 * @brief Send a scaled_pressure message
119
 * @param chan MAVLink channel to send the message
120
 *
121
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
122
 * @param press_abs Absolute pressure (hectopascal)
123
 * @param press_diff Differential pressure 1 (hectopascal)
124
 * @param temperature Temperature measurement (0.01 degrees celsius)
125
 */
126
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
127
 
128
static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff, int16_t temperature)
129
{
130
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
131
        char buf[18];
132
        _mav_put_uint64_t(buf, 0, usec);
133
        _mav_put_float(buf, 8, press_abs);
134
        _mav_put_float(buf, 12, press_diff);
135
        _mav_put_int16_t(buf, 16, temperature);
136
 
137
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, 18);
138
#else
139
        mavlink_scaled_pressure_t packet;
140
        packet.usec = usec;
141
        packet.press_abs = press_abs;
142
        packet.press_diff = press_diff;
143
        packet.temperature = temperature;
144
 
145
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, 18);
146
#endif
147
}
148
 
149
#endif
150
 
151
// MESSAGE SCALED_PRESSURE UNPACKING
152
 
153
 
154
/**
155
 * @brief Get field usec from scaled_pressure message
156
 *
157
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
158
 */
159
static inline uint64_t mavlink_msg_scaled_pressure_get_usec(const mavlink_message_t* msg)
160
{
161
        return _MAV_RETURN_uint64_t(msg,  0);
162
}
163
 
164
/**
165
 * @brief Get field press_abs from scaled_pressure message
166
 *
167
 * @return Absolute pressure (hectopascal)
168
 */
169
static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg)
170
{
171
        return _MAV_RETURN_float(msg,  8);
172
}
173
 
174
/**
175
 * @brief Get field press_diff from scaled_pressure message
176
 *
177
 * @return Differential pressure 1 (hectopascal)
178
 */
179
static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg)
180
{
181
        return _MAV_RETURN_float(msg,  12);
182
}
183
 
184
/**
185
 * @brief Get field temperature from scaled_pressure message
186
 *
187
 * @return Temperature measurement (0.01 degrees celsius)
188
 */
189
static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg)
190
{
191
        return _MAV_RETURN_int16_t(msg,  16);
192
}
193
 
194
/**
195
 * @brief Decode a scaled_pressure message into a struct
196
 *
197
 * @param msg The message to decode
198
 * @param scaled_pressure C-struct to decode the message contents into
199
 */
200
static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure)
201
{
202
#if MAVLINK_NEED_BYTE_SWAP
203
        scaled_pressure->usec = mavlink_msg_scaled_pressure_get_usec(msg);
204
        scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
205
        scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
206
        scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
207
#else
208
        memcpy(scaled_pressure, _MAV_PAYLOAD(msg), 18);
209
#endif
210
}