Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE MISSION_ACK PACKING
2
 
3
#define MAVLINK_MSG_ID_MISSION_ACK 47
4
 
5
typedef struct __mavlink_mission_ack_t
6
{
7
 uint8_t target_system; ///< System ID
8
 uint8_t target_component; ///< Component ID
9
 uint8_t type; ///< See MAV_MISSION_RESULT enum
10
} mavlink_mission_ack_t;
11
 
12
#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3
13
#define MAVLINK_MSG_ID_47_LEN 3
14
 
15
 
16
 
17
#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \
18
        "MISSION_ACK", \
19
        3, \
20
        {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \
21
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \
22
         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \
23
         } \
24
}
25
 
26
 
27
/**
28
 * @brief Pack a mission_ack 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 type See MAV_MISSION_RESULT enum
36
 * @return length of the message in bytes (excluding serial stream start sign)
37
 */
38
static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39
                                                       uint8_t target_system, uint8_t target_component, uint8_t type)
40
{
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42
        char buf[3];
43
        _mav_put_uint8_t(buf, 0, target_system);
44
        _mav_put_uint8_t(buf, 1, target_component);
45
        _mav_put_uint8_t(buf, 2, type);
46
 
47
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
48
#else
49
        mavlink_mission_ack_t packet;
50
        packet.target_system = target_system;
51
        packet.target_component = target_component;
52
        packet.type = type;
53
 
54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
55
#endif
56
 
57
        msg->msgid = MAVLINK_MSG_ID_MISSION_ACK;
58
        return mavlink_finalize_message(msg, system_id, component_id, 3, 153);
59
}
60
 
61
/**
62
 * @brief Pack a mission_ack 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 type See MAV_MISSION_RESULT enum
70
 * @return length of the message in bytes (excluding serial stream start sign)
71
 */
72
static inline uint16_t mavlink_msg_mission_ack_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,uint8_t type)
75
{
76
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
77
        char buf[3];
78
        _mav_put_uint8_t(buf, 0, target_system);
79
        _mav_put_uint8_t(buf, 1, target_component);
80
        _mav_put_uint8_t(buf, 2, type);
81
 
82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
83
#else
84
        mavlink_mission_ack_t packet;
85
        packet.target_system = target_system;
86
        packet.target_component = target_component;
87
        packet.type = type;
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
90
#endif
91
 
92
        msg->msgid = MAVLINK_MSG_ID_MISSION_ACK;
93
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 153);
94
}
95
 
96
/**
97
 * @brief Encode a mission_ack 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_ack C-struct to read the message contents from
103
 */
104
static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack)
105
{
106
        return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type);
107
}
108
 
109
/**
110
 * @brief Send a mission_ack 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 type See MAV_MISSION_RESULT enum
116
 */
117
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
118
 
119
static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
120
{
121
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122
        char buf[3];
123
        _mav_put_uint8_t(buf, 0, target_system);
124
        _mav_put_uint8_t(buf, 1, target_component);
125
        _mav_put_uint8_t(buf, 2, type);
126
 
127
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, 3, 153);
128
#else
129
        mavlink_mission_ack_t packet;
130
        packet.target_system = target_system;
131
        packet.target_component = target_component;
132
        packet.type = type;
133
 
134
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, 3, 153);
135
#endif
136
}
137
 
138
#endif
139
 
140
// MESSAGE MISSION_ACK UNPACKING
141
 
142
 
143
/**
144
 * @brief Get field target_system from mission_ack message
145
 *
146
 * @return System ID
147
 */
148
static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg)
149
{
150
        return _MAV_RETURN_uint8_t(msg,  0);
151
}
152
 
153
/**
154
 * @brief Get field target_component from mission_ack message
155
 *
156
 * @return Component ID
157
 */
158
static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg)
159
{
160
        return _MAV_RETURN_uint8_t(msg,  1);
161
}
162
 
163
/**
164
 * @brief Get field type from mission_ack message
165
 *
166
 * @return See MAV_MISSION_RESULT enum
167
 */
168
static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg)
169
{
170
        return _MAV_RETURN_uint8_t(msg,  2);
171
}
172
 
173
/**
174
 * @brief Decode a mission_ack message into a struct
175
 *
176
 * @param msg The message to decode
177
 * @param mission_ack C-struct to decode the message contents into
178
 */
179
static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack)
180
{
181
#if MAVLINK_NEED_BYTE_SWAP
182
        mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg);
183
        mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg);
184
        mission_ack->type = mavlink_msg_mission_ack_get_type(msg);
185
#else
186
        memcpy(mission_ack, _MAV_PAYLOAD(msg), 3);
187
#endif
188
}