Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT PACKING
2
 
3
#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53
4
 
5
typedef struct __mavlink_set_global_position_setpoint_int_t
6
{
7
 int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7
8
 int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7
9
 int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up)
10
 int16_t yaw; ///< Desired yaw angle in degrees * 100
11
 uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
12
} mavlink_set_global_position_setpoint_int_t;
13
 
14
#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15
15
#define MAVLINK_MSG_ID_53_LEN 15
16
 
17
 
18
 
19
#define MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT { \
20
        "SET_GLOBAL_POSITION_SETPOINT_INT", \
21
        5, \
22
        {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_global_position_setpoint_int_t, latitude) }, \
23
         { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_global_position_setpoint_int_t, longitude) }, \
24
         { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_global_position_setpoint_int_t, altitude) }, \
25
         { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_set_global_position_setpoint_int_t, yaw) }, \
26
         { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_global_position_setpoint_int_t, coordinate_frame) }, \
27
         } \
28
}
29
 
30
 
31
/**
32
 * @brief Pack a set_global_position_setpoint_int message
33
 * @param system_id ID of this system
34
 * @param component_id ID of this component (e.g. 200 for IMU)
35
 * @param msg The MAVLink message to compress the data into
36
 *
37
 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
38
 * @param latitude WGS84 Latitude position in degrees * 1E7
39
 * @param longitude WGS84 Longitude position in degrees * 1E7
40
 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
41
 * @param yaw Desired yaw angle in degrees * 100
42
 * @return length of the message in bytes (excluding serial stream start sign)
43
 */
44
static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
                                                       uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
46
{
47
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
48
        char buf[15];
49
        _mav_put_int32_t(buf, 0, latitude);
50
        _mav_put_int32_t(buf, 4, longitude);
51
        _mav_put_int32_t(buf, 8, altitude);
52
        _mav_put_int16_t(buf, 12, yaw);
53
        _mav_put_uint8_t(buf, 14, coordinate_frame);
54
 
55
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
56
#else
57
        mavlink_set_global_position_setpoint_int_t packet;
58
        packet.latitude = latitude;
59
        packet.longitude = longitude;
60
        packet.altitude = altitude;
61
        packet.yaw = yaw;
62
        packet.coordinate_frame = coordinate_frame;
63
 
64
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
65
#endif
66
 
67
        msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT;
68
        return mavlink_finalize_message(msg, system_id, component_id, 15, 33);
69
}
70
 
71
/**
72
 * @brief Pack a set_global_position_setpoint_int message on a channel
73
 * @param system_id ID of this system
74
 * @param component_id ID of this component (e.g. 200 for IMU)
75
 * @param chan The MAVLink channel this message was sent over
76
 * @param msg The MAVLink message to compress the data into
77
 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
78
 * @param latitude WGS84 Latitude position in degrees * 1E7
79
 * @param longitude WGS84 Longitude position in degrees * 1E7
80
 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
81
 * @param yaw Desired yaw angle in degrees * 100
82
 * @return length of the message in bytes (excluding serial stream start sign)
83
 */
84
static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
85
                                                           mavlink_message_t* msg,
86
                                                           uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw)
87
{
88
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
89
        char buf[15];
90
        _mav_put_int32_t(buf, 0, latitude);
91
        _mav_put_int32_t(buf, 4, longitude);
92
        _mav_put_int32_t(buf, 8, altitude);
93
        _mav_put_int16_t(buf, 12, yaw);
94
        _mav_put_uint8_t(buf, 14, coordinate_frame);
95
 
96
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
97
#else
98
        mavlink_set_global_position_setpoint_int_t packet;
99
        packet.latitude = latitude;
100
        packet.longitude = longitude;
101
        packet.altitude = altitude;
102
        packet.yaw = yaw;
103
        packet.coordinate_frame = coordinate_frame;
104
 
105
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
106
#endif
107
 
108
        msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT;
109
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 33);
110
}
111
 
112
/**
113
 * @brief Encode a set_global_position_setpoint_int struct into a message
114
 *
115
 * @param system_id ID of this system
116
 * @param component_id ID of this component (e.g. 200 for IMU)
117
 * @param msg The MAVLink message to compress the data into
118
 * @param set_global_position_setpoint_int C-struct to read the message contents from
119
 */
120
static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int)
121
{
122
        return mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw);
123
}
124
 
125
/**
126
 * @brief Send a set_global_position_setpoint_int message
127
 * @param chan MAVLink channel to send the message
128
 *
129
 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
130
 * @param latitude WGS84 Latitude position in degrees * 1E7
131
 * @param longitude WGS84 Longitude position in degrees * 1E7
132
 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
133
 * @param yaw Desired yaw angle in degrees * 100
134
 */
135
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
136
 
137
static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
138
{
139
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
140
        char buf[15];
141
        _mav_put_int32_t(buf, 0, latitude);
142
        _mav_put_int32_t(buf, 4, longitude);
143
        _mav_put_int32_t(buf, 8, altitude);
144
        _mav_put_int16_t(buf, 12, yaw);
145
        _mav_put_uint8_t(buf, 14, coordinate_frame);
146
 
147
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 33);
148
#else
149
        mavlink_set_global_position_setpoint_int_t packet;
150
        packet.latitude = latitude;
151
        packet.longitude = longitude;
152
        packet.altitude = altitude;
153
        packet.yaw = yaw;
154
        packet.coordinate_frame = coordinate_frame;
155
 
156
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 33);
157
#endif
158
}
159
 
160
#endif
161
 
162
// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT UNPACKING
163
 
164
 
165
/**
166
 * @brief Get field coordinate_frame from set_global_position_setpoint_int message
167
 *
168
 * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
169
 */
170
static inline uint8_t mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg)
171
{
172
        return _MAV_RETURN_uint8_t(msg,  14);
173
}
174
 
175
/**
176
 * @brief Get field latitude from set_global_position_setpoint_int message
177
 *
178
 * @return WGS84 Latitude position in degrees * 1E7
179
 */
180
static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg)
181
{
182
        return _MAV_RETURN_int32_t(msg,  0);
183
}
184
 
185
/**
186
 * @brief Get field longitude from set_global_position_setpoint_int message
187
 *
188
 * @return WGS84 Longitude position in degrees * 1E7
189
 */
190
static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg)
191
{
192
        return _MAV_RETURN_int32_t(msg,  4);
193
}
194
 
195
/**
196
 * @brief Get field altitude from set_global_position_setpoint_int message
197
 *
198
 * @return WGS84 Altitude in meters * 1000 (positive for up)
199
 */
200
static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg)
201
{
202
        return _MAV_RETURN_int32_t(msg,  8);
203
}
204
 
205
/**
206
 * @brief Get field yaw from set_global_position_setpoint_int message
207
 *
208
 * @return Desired yaw angle in degrees * 100
209
 */
210
static inline int16_t mavlink_msg_set_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg)
211
{
212
        return _MAV_RETURN_int16_t(msg,  12);
213
}
214
 
215
/**
216
 * @brief Decode a set_global_position_setpoint_int message into a struct
217
 *
218
 * @param msg The message to decode
219
 * @param set_global_position_setpoint_int C-struct to decode the message contents into
220
 */
221
static inline void mavlink_msg_set_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int)
222
{
223
#if MAVLINK_NEED_BYTE_SWAP
224
        set_global_position_setpoint_int->latitude = mavlink_msg_set_global_position_setpoint_int_get_latitude(msg);
225
        set_global_position_setpoint_int->longitude = mavlink_msg_set_global_position_setpoint_int_get_longitude(msg);
226
        set_global_position_setpoint_int->altitude = mavlink_msg_set_global_position_setpoint_int_get_altitude(msg);
227
        set_global_position_setpoint_int->yaw = mavlink_msg_set_global_position_setpoint_int_get_yaw(msg);
228
        set_global_position_setpoint_int->coordinate_frame = mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(msg);
229
#else
230
        memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), 15);
231
#endif
232
}