mavlink_msg_data_log.h 7.17 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE DATA_LOG PACKING

#define MAVLINK_MSG_ID_DATA_LOG 177

lm's avatar
lm committed
5
typedef struct __mavlink_data_log_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11 12
 float fl_1; ///< Log value 1 
 float fl_2; ///< Log value 2 
 float fl_3; ///< Log value 3 
 float fl_4; ///< Log value 4 
 float fl_5; ///< Log value 5 
 float fl_6; ///< Log value 6 
James Goppert's avatar
James Goppert committed
13 14
} mavlink_data_log_t;

lm's avatar
lm committed
15 16 17 18 19 20 21 22
#define MAVLINK_MSG_ID_DATA_LOG_LEN 24
#define MAVLINK_MSG_ID_177_LEN 24



#define MAVLINK_MESSAGE_INFO_DATA_LOG { \
	"DATA_LOG", \
	6, \
lm's avatar
lm committed
23 24 25 26 27 28
	{  { "fl_1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_data_log_t, fl_1) }, \
         { "fl_2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_data_log_t, fl_2) }, \
         { "fl_3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_data_log_t, fl_3) }, \
         { "fl_4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_data_log_t, fl_4) }, \
         { "fl_5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_data_log_t, fl_5) }, \
         { "fl_6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_data_log_t, fl_6) }, \
lm's avatar
lm committed
29 30 31 32
         } \
}


James Goppert's avatar
James Goppert committed
33
/**
James Goppert's avatar
James Goppert committed
34 35 36 37
 * @brief Pack a data_log message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
James Goppert's avatar
James Goppert committed
38 39 40 41 42 43 44 45 46
 *
 * @param fl_1 Log value 1 
 * @param fl_2 Log value 2 
 * @param fl_3 Log value 3 
 * @param fl_4 Log value 4 
 * @param fl_5 Log value 5 
 * @param fl_6 Log value 6 
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
47 48
static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
James Goppert's avatar
James Goppert committed
49
{
LM's avatar
LM committed
50 51 52 53 54 55 56 57 58
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_float(buf, 0, fl_1);
	_mav_put_float(buf, 4, fl_2);
	_mav_put_float(buf, 8, fl_3);
	_mav_put_float(buf, 12, fl_4);
	_mav_put_float(buf, 16, fl_5);
	_mav_put_float(buf, 20, fl_6);

59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
LM's avatar
LM committed
60 61 62 63 64 65 66 67 68
#else
	mavlink_data_log_t packet;
	packet.fl_1 = fl_1;
	packet.fl_2 = fl_2;
	packet.fl_3 = fl_3;
	packet.fl_4 = fl_4;
	packet.fl_5 = fl_5;
	packet.fl_6 = fl_6;

69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
LM's avatar
LM committed
70
#endif
James Goppert's avatar
James Goppert committed
71

LM's avatar
LM committed
72
	msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
lm's avatar
lm committed
73
	return mavlink_finalize_message(msg, system_id, component_id, 24, 167);
James Goppert's avatar
James Goppert committed
74 75
}

James Goppert's avatar
James Goppert committed
76
/**
lm's avatar
lm committed
77
 * @brief Pack a data_log message on a channel
James Goppert's avatar
James Goppert committed
78 79 80 81 82 83 84 85 86 87 88 89
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param fl_1 Log value 1 
 * @param fl_2 Log value 2 
 * @param fl_3 Log value 3 
 * @param fl_4 Log value 4 
 * @param fl_5 Log value 5 
 * @param fl_6 Log value 6 
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
90 91 92 93
static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           float fl_1,float fl_2,float fl_3,float fl_4,float fl_5,float fl_6)
{
LM's avatar
LM committed
94 95 96 97 98 99 100 101 102
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_float(buf, 0, fl_1);
	_mav_put_float(buf, 4, fl_2);
	_mav_put_float(buf, 8, fl_3);
	_mav_put_float(buf, 12, fl_4);
	_mav_put_float(buf, 16, fl_5);
	_mav_put_float(buf, 20, fl_6);

103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
LM's avatar
LM committed
104 105 106 107 108 109 110 111 112
#else
	mavlink_data_log_t packet;
	packet.fl_1 = fl_1;
	packet.fl_2 = fl_2;
	packet.fl_3 = fl_3;
	packet.fl_4 = fl_4;
	packet.fl_5 = fl_5;
	packet.fl_6 = fl_6;

113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
LM's avatar
LM committed
114
#endif
lm's avatar
lm committed
115

LM's avatar
LM committed
116
	msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
lm's avatar
lm committed
117 118 119
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 167);
}

James Goppert's avatar
James Goppert committed
120 121 122 123 124 125 126 127
/**
 * @brief Encode a data_log struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param data_log C-struct to read the message contents from
 */
James Goppert's avatar
James Goppert committed
128 129 130 131 132
static inline uint16_t mavlink_msg_data_log_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_log_t* data_log)
{
	return mavlink_msg_data_log_pack(system_id, component_id, msg, data_log->fl_1, data_log->fl_2, data_log->fl_3, data_log->fl_4, data_log->fl_5, data_log->fl_6);
}

James Goppert's avatar
James Goppert committed
133 134 135 136 137 138 139 140 141 142 143
/**
 * @brief Send a data_log message
 * @param chan MAVLink channel to send the message
 *
 * @param fl_1 Log value 1 
 * @param fl_2 Log value 2 
 * @param fl_3 Log value 3 
 * @param fl_4 Log value 4 
 * @param fl_5 Log value 5 
 * @param fl_6 Log value 6 
 */
lm's avatar
lm committed
144 145
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
146 147
static inline void mavlink_msg_data_log_send(mavlink_channel_t chan, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
{
LM's avatar
LM committed
148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_float(buf, 0, fl_1);
	_mav_put_float(buf, 4, fl_2);
	_mav_put_float(buf, 8, fl_3);
	_mav_put_float(buf, 12, fl_4);
	_mav_put_float(buf, 16, fl_5);
	_mav_put_float(buf, 20, fl_6);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_LOG, buf, 24, 167);
#else
	mavlink_data_log_t packet;
	packet.fl_1 = fl_1;
	packet.fl_2 = fl_2;
	packet.fl_3 = fl_3;
	packet.fl_4 = fl_4;
	packet.fl_5 = fl_5;
	packet.fl_6 = fl_6;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_LOG, (const char *)&packet, 24, 167);
#endif
James Goppert's avatar
James Goppert committed
169 170 171
}

#endif
lm's avatar
lm committed
172

James Goppert's avatar
James Goppert committed
173 174
// MESSAGE DATA_LOG UNPACKING

lm's avatar
lm committed
175

James Goppert's avatar
James Goppert committed
176 177 178 179 180 181 182
/**
 * @brief Get field fl_1 from data_log message
 *
 * @return Log value 1 
 */
static inline float mavlink_msg_data_log_get_fl_1(const mavlink_message_t* msg)
{
LM's avatar
LM committed
183
	return _MAV_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
184 185 186 187 188 189 190 191 192
}

/**
 * @brief Get field fl_2 from data_log message
 *
 * @return Log value 2 
 */
static inline float mavlink_msg_data_log_get_fl_2(const mavlink_message_t* msg)
{
LM's avatar
LM committed
193
	return _MAV_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
194 195 196 197 198 199 200 201 202
}

/**
 * @brief Get field fl_3 from data_log message
 *
 * @return Log value 3 
 */
static inline float mavlink_msg_data_log_get_fl_3(const mavlink_message_t* msg)
{
LM's avatar
LM committed
203
	return _MAV_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
204 205 206 207 208 209 210 211 212
}

/**
 * @brief Get field fl_4 from data_log message
 *
 * @return Log value 4 
 */
static inline float mavlink_msg_data_log_get_fl_4(const mavlink_message_t* msg)
{
LM's avatar
LM committed
213
	return _MAV_RETURN_float(msg,  12);
James Goppert's avatar
James Goppert committed
214 215 216 217 218 219 220 221 222
}

/**
 * @brief Get field fl_5 from data_log message
 *
 * @return Log value 5 
 */
static inline float mavlink_msg_data_log_get_fl_5(const mavlink_message_t* msg)
{
LM's avatar
LM committed
223
	return _MAV_RETURN_float(msg,  16);
James Goppert's avatar
James Goppert committed
224 225 226 227 228 229 230 231 232
}

/**
 * @brief Get field fl_6 from data_log message
 *
 * @return Log value 6 
 */
static inline float mavlink_msg_data_log_get_fl_6(const mavlink_message_t* msg)
{
LM's avatar
LM committed
233
	return _MAV_RETURN_float(msg,  20);
James Goppert's avatar
James Goppert committed
234 235
}

James Goppert's avatar
James Goppert committed
236 237 238 239 240 241
/**
 * @brief Decode a data_log message into a struct
 *
 * @param msg The message to decode
 * @param data_log C-struct to decode the message contents into
 */
James Goppert's avatar
James Goppert committed
242 243
static inline void mavlink_msg_data_log_decode(const mavlink_message_t* msg, mavlink_data_log_t* data_log)
{
lm's avatar
lm committed
244 245 246 247 248 249 250 251
#if MAVLINK_NEED_BYTE_SWAP
	data_log->fl_1 = mavlink_msg_data_log_get_fl_1(msg);
	data_log->fl_2 = mavlink_msg_data_log_get_fl_2(msg);
	data_log->fl_3 = mavlink_msg_data_log_get_fl_3(msg);
	data_log->fl_4 = mavlink_msg_data_log_get_fl_4(msg);
	data_log->fl_5 = mavlink_msg_data_log_get_fl_5(msg);
	data_log->fl_6 = mavlink_msg_data_log_get_fl_6(msg);
#else
LM's avatar
LM committed
252
	memcpy(data_log, _MAV_PAYLOAD(msg), 24);
lm's avatar
lm committed
253
#endif
James Goppert's avatar
James Goppert committed
254
}