Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE MISSION_REQUEST PACKING
2
 
3
#define MAVLINK_MSG_ID_MISSION_REQUEST 40
4
 
5
typedef struct __mavlink_mission_request_t
6
{
7
 uint16_t seq; ///< Sequence
8
 uint8_t target_system; ///< System ID
9
 uint8_t target_component; ///< Component ID
10
} mavlink_mission_request_t;
11
 
12
#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4
13
#define MAVLINK_MSG_ID_40_LEN 4
14
 
15
 
16
 
17
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
18
        "MISSION_REQUEST", \
19
        3, \
20
        {  { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
21
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
22
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \
23
         } \
24
}
25
 
26
 
27
/**
28
 * @brief Pack a mission_request message
29
 * @param system_id ID of this system
30
 * @param component_id ID of this component (e.g. 200 for IMU)
31
 * @param msg The MAVLink message to compress the data into
32
 *
33
 * @param target_system System ID
34
 * @param target_component Component ID
35
 * @param seq Sequence
36
 * @return length of the message in bytes (excluding serial stream start sign)
37
 */
38
static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39
                                                       uint8_t target_system, uint8_t target_component, uint16_t seq)
40
{
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42
        char buf[4];
43
        _mav_put_uint16_t(buf, 0, seq);
44
        _mav_put_uint8_t(buf, 2, target_system);
45
        _mav_put_uint8_t(buf, 3, target_component);
46
 
47
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
48
#else
49
        mavlink_mission_request_t packet;
50
        packet.seq = seq;
51
        packet.target_system = target_system;
52
        packet.target_component = target_component;
53
 
54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
55
#endif
56
 
57
        msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
58
        return mavlink_finalize_message(msg, system_id, component_id, 4, 230);
59
}
60
 
61
/**
62
 * @brief Pack a mission_request message on a channel
63
 * @param system_id ID of this system
64
 * @param component_id ID of this component (e.g. 200 for IMU)
65
 * @param chan The MAVLink channel this message was sent over
66
 * @param msg The MAVLink message to compress the data into
67
 * @param target_system System ID
68
 * @param target_component Component ID
69
 * @param seq Sequence
70
 * @return length of the message in bytes (excluding serial stream start sign)
71
 */
72
static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
73
                                                           mavlink_message_t* msg,
74
                                                           uint8_t target_system,uint8_t target_component,uint16_t seq)
75
{
76
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
77
        char buf[4];
78
        _mav_put_uint16_t(buf, 0, seq);
79
        _mav_put_uint8_t(buf, 2, target_system);
80
        _mav_put_uint8_t(buf, 3, target_component);
81
 
82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
83
#else
84
        mavlink_mission_request_t packet;
85
        packet.seq = seq;
86
        packet.target_system = target_system;
87
        packet.target_component = target_component;
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
90
#endif
91
 
92
        msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
93
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 230);
94
}
95
 
96
/**
97
 * @brief Encode a mission_request struct into a message
98
 *
99
 * @param system_id ID of this system
100
 * @param component_id ID of this component (e.g. 200 for IMU)
101
 * @param msg The MAVLink message to compress the data into
102
 * @param mission_request C-struct to read the message contents from
103
 */
104
static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
105
{
106
        return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq);
107
}
108
 
109
/**
110
 * @brief Send a mission_request message
111
 * @param chan MAVLink channel to send the message
112
 *
113
 * @param target_system System ID
114
 * @param target_component Component ID
115
 * @param seq Sequence
116
 */
117
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
118
 
119
static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
120
{
121
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122
        char buf[4];
123
        _mav_put_uint16_t(buf, 0, seq);
124
        _mav_put_uint8_t(buf, 2, target_system);
125
        _mav_put_uint8_t(buf, 3, target_component);
126
 
127
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, 4, 230);
128
#else
129
        mavlink_mission_request_t packet;
130
        packet.seq = seq;
131
        packet.target_system = target_system;
132
        packet.target_component = target_component;
133
 
134
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, 4, 230);
135
#endif
136
}
137
 
138
#endif
139
 
140
// MESSAGE MISSION_REQUEST UNPACKING
141
 
142
 
143
/**
144
 * @brief Get field target_system from mission_request message
145
 *
146
 * @return System ID
147
 */
148
static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg)
149
{
150
        return _MAV_RETURN_uint8_t(msg,  2);
151
}
152
 
153
/**
154
 * @brief Get field target_component from mission_request message
155
 *
156
 * @return Component ID
157
 */
158
static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg)
159
{
160
        return _MAV_RETURN_uint8_t(msg,  3);
161
}
162
 
163
/**
164
 * @brief Get field seq from mission_request message
165
 *
166
 * @return Sequence
167
 */
168
static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg)
169
{
170
        return _MAV_RETURN_uint16_t(msg,  0);
171
}
172
 
173
/**
174
 * @brief Decode a mission_request message into a struct
175
 *
176
 * @param msg The message to decode
177
 * @param mission_request C-struct to decode the message contents into
178
 */
179
static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request)
180
{
181
#if MAVLINK_NEED_BYTE_SWAP
182
        mission_request->seq = mavlink_msg_mission_request_get_seq(msg);
183
        mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg);
184
        mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg);
185
#else
186
        memcpy(mission_request, _MAV_PAYLOAD(msg), 4);
187
#endif
188
}