Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE OBS_POSITION PACKING
2
 
3
#define MAVLINK_MSG_ID_OBS_POSITION 170
4
 
5
typedef struct __mavlink_obs_position_t
6
{
7
 int32_t lon; ///< Longitude expressed in 1E7
8
 int32_t lat; ///< Latitude expressed in 1E7
9
 int32_t alt; ///< Altitude expressed in milimeters
10
} mavlink_obs_position_t;
11
 
12
#define MAVLINK_MSG_ID_OBS_POSITION_LEN 12
13
#define MAVLINK_MSG_ID_170_LEN 12
14
 
15
 
16
 
17
#define MAVLINK_MESSAGE_INFO_OBS_POSITION { \
18
        "OBS_POSITION", \
19
        3, \
20
        {  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_obs_position_t, lon) }, \
21
         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_obs_position_t, lat) }, \
22
         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_obs_position_t, alt) }, \
23
         } \
24
}
25
 
26
 
27
/**
28
 * @brief Pack a obs_position 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 lon Longitude expressed in 1E7
34
 * @param lat Latitude expressed in 1E7
35
 * @param alt Altitude expressed in milimeters
36
 * @return length of the message in bytes (excluding serial stream start sign)
37
 */
38
static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39
                                                       int32_t lon, int32_t lat, int32_t alt)
40
{
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42
        char buf[12];
43
        _mav_put_int32_t(buf, 0, lon);
44
        _mav_put_int32_t(buf, 4, lat);
45
        _mav_put_int32_t(buf, 8, alt);
46
 
47
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
48
#else
49
        mavlink_obs_position_t packet;
50
        packet.lon = lon;
51
        packet.lat = lat;
52
        packet.alt = alt;
53
 
54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
55
#endif
56
 
57
        msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
58
        return mavlink_finalize_message(msg, system_id, component_id, 12, 15);
59
}
60
 
61
/**
62
 * @brief Pack a obs_position 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 lon Longitude expressed in 1E7
68
 * @param lat Latitude expressed in 1E7
69
 * @param alt Altitude expressed in milimeters
70
 * @return length of the message in bytes (excluding serial stream start sign)
71
 */
72
static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
73
                                                           mavlink_message_t* msg,
74
                                                           int32_t lon,int32_t lat,int32_t alt)
75
{
76
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
77
        char buf[12];
78
        _mav_put_int32_t(buf, 0, lon);
79
        _mav_put_int32_t(buf, 4, lat);
80
        _mav_put_int32_t(buf, 8, alt);
81
 
82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
83
#else
84
        mavlink_obs_position_t packet;
85
        packet.lon = lon;
86
        packet.lat = lat;
87
        packet.alt = alt;
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
90
#endif
91
 
92
        msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
93
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 15);
94
}
95
 
96
/**
97
 * @brief Encode a obs_position 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 obs_position C-struct to read the message contents from
103
 */
104
static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position)
105
{
106
        return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->lon, obs_position->lat, obs_position->alt);
107
}
108
 
109
/**
110
 * @brief Send a obs_position message
111
 * @param chan MAVLink channel to send the message
112
 *
113
 * @param lon Longitude expressed in 1E7
114
 * @param lat Latitude expressed in 1E7
115
 * @param alt Altitude expressed in milimeters
116
 */
117
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
118
 
119
static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt)
120
{
121
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122
        char buf[12];
123
        _mav_put_int32_t(buf, 0, lon);
124
        _mav_put_int32_t(buf, 4, lat);
125
        _mav_put_int32_t(buf, 8, alt);
126
 
127
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, 12, 15);
128
#else
129
        mavlink_obs_position_t packet;
130
        packet.lon = lon;
131
        packet.lat = lat;
132
        packet.alt = alt;
133
 
134
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, 12, 15);
135
#endif
136
}
137
 
138
#endif
139
 
140
// MESSAGE OBS_POSITION UNPACKING
141
 
142
 
143
/**
144
 * @brief Get field lon from obs_position message
145
 *
146
 * @return Longitude expressed in 1E7
147
 */
148
static inline int32_t mavlink_msg_obs_position_get_lon(const mavlink_message_t* msg)
149
{
150
        return _MAV_RETURN_int32_t(msg,  0);
151
}
152
 
153
/**
154
 * @brief Get field lat from obs_position message
155
 *
156
 * @return Latitude expressed in 1E7
157
 */
158
static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t* msg)
159
{
160
        return _MAV_RETURN_int32_t(msg,  4);
161
}
162
 
163
/**
164
 * @brief Get field alt from obs_position message
165
 *
166
 * @return Altitude expressed in milimeters
167
 */
168
static inline int32_t mavlink_msg_obs_position_get_alt(const mavlink_message_t* msg)
169
{
170
        return _MAV_RETURN_int32_t(msg,  8);
171
}
172
 
173
/**
174
 * @brief Decode a obs_position message into a struct
175
 *
176
 * @param msg The message to decode
177
 * @param obs_position C-struct to decode the message contents into
178
 */
179
static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, mavlink_obs_position_t* obs_position)
180
{
181
#if MAVLINK_NEED_BYTE_SWAP
182
        obs_position->lon = mavlink_msg_obs_position_get_lon(msg);
183
        obs_position->lat = mavlink_msg_obs_position_get_lat(msg);
184
        obs_position->alt = mavlink_msg_obs_position_get_alt(msg);
185
#else
186
        memcpy(obs_position, _MAV_PAYLOAD(msg), 12);
187
#endif
188
}