Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

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