mavlink_msg_watchdog_command.h 7.02 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE WATCHDOG_COMMAND PACKING

lm's avatar
lm committed
3
#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 183
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_watchdog_command_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10
 uint16_t watchdog_id; ///< Watchdog ID
 uint16_t process_id; ///< Process ID
 uint8_t target_system_id; ///< Target system ID
 uint8_t command_id; ///< Command ID
James Goppert's avatar
James Goppert committed
11 12
} mavlink_watchdog_command_t;

lm's avatar
lm committed
13 14 15 16 17 18 19 20
#define MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN 6
#define MAVLINK_MSG_ID_183_LEN 6



#define MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND { \
	"WATCHDOG_COMMAND", \
	4, \
lm's avatar
lm committed
21 22 23 24
	{  { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_command_t, watchdog_id) }, \
         { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_command_t, process_id) }, \
         { "target_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_watchdog_command_t, target_system_id) }, \
         { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_command_t, command_id) }, \
lm's avatar
lm committed
25 26 27 28
         } \
}


James Goppert's avatar
James Goppert committed
29 30 31 32 33 34 35 36 37 38 39 40
/**
 * @brief Pack a watchdog_command 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 target_system_id Target system ID
 * @param watchdog_id Watchdog ID
 * @param process_id Process ID
 * @param command_id Command ID
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
41 42
static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
James Goppert's avatar
James Goppert committed
43
{
LM's avatar
LM committed
44 45 46 47 48 49 50 51 52 53 54 55 56 57
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[6];
	_mav_put_uint16_t(buf, 0, watchdog_id);
	_mav_put_uint16_t(buf, 2, process_id);
	_mav_put_uint8_t(buf, 4, target_system_id);
	_mav_put_uint8_t(buf, 5, command_id);

        memcpy(_MAV_PAYLOAD(msg), buf, 6);
#else
	mavlink_watchdog_command_t packet;
	packet.watchdog_id = watchdog_id;
	packet.process_id = process_id;
	packet.target_system_id = target_system_id;
	packet.command_id = command_id;
James Goppert's avatar
James Goppert committed
58

LM's avatar
LM committed
59 60
        memcpy(_MAV_PAYLOAD(msg), &packet, 6);
#endif
James Goppert's avatar
James Goppert committed
61

LM's avatar
LM committed
62
	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
lm's avatar
lm committed
63
	return mavlink_finalize_message(msg, system_id, component_id, 6, 162);
James Goppert's avatar
James Goppert committed
64 65 66
}

/**
lm's avatar
lm committed
67
 * @brief Pack a watchdog_command message on a channel
James Goppert's avatar
James Goppert committed
68 69 70 71 72 73 74 75 76 77
 * @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 target_system_id Target system ID
 * @param watchdog_id Watchdog ID
 * @param process_id Process ID
 * @param command_id Command ID
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
78 79 80 81
static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint8_t target_system_id,uint16_t watchdog_id,uint16_t process_id,uint8_t command_id)
{
LM's avatar
LM committed
82 83 84 85 86 87 88 89 90 91 92 93 94 95
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[6];
	_mav_put_uint16_t(buf, 0, watchdog_id);
	_mav_put_uint16_t(buf, 2, process_id);
	_mav_put_uint8_t(buf, 4, target_system_id);
	_mav_put_uint8_t(buf, 5, command_id);

        memcpy(_MAV_PAYLOAD(msg), buf, 6);
#else
	mavlink_watchdog_command_t packet;
	packet.watchdog_id = watchdog_id;
	packet.process_id = process_id;
	packet.target_system_id = target_system_id;
	packet.command_id = command_id;
lm's avatar
lm committed
96

LM's avatar
LM committed
97 98
        memcpy(_MAV_PAYLOAD(msg), &packet, 6);
#endif
lm's avatar
lm committed
99

LM's avatar
LM committed
100
	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
lm's avatar
lm committed
101 102 103
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 162);
}

James Goppert's avatar
James Goppert committed
104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125
/**
 * @brief Encode a watchdog_command 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 watchdog_command C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command)
{
	return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
}

/**
 * @brief Send a watchdog_command message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system_id Target system ID
 * @param watchdog_id Watchdog ID
 * @param process_id Process ID
 * @param command_id Command ID
 */
lm's avatar
lm committed
126 127
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
128 129
static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
{
LM's avatar
LM committed
130 131 132 133 134 135 136 137 138 139 140 141 142 143
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[6];
	_mav_put_uint16_t(buf, 0, watchdog_id);
	_mav_put_uint16_t(buf, 2, process_id);
	_mav_put_uint8_t(buf, 4, target_system_id);
	_mav_put_uint8_t(buf, 5, command_id);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, 6, 162);
#else
	mavlink_watchdog_command_t packet;
	packet.watchdog_id = watchdog_id;
	packet.process_id = process_id;
	packet.target_system_id = target_system_id;
	packet.command_id = command_id;
LM's avatar
LM committed
144

LM's avatar
LM committed
145 146
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, 6, 162);
#endif
James Goppert's avatar
James Goppert committed
147 148 149
}

#endif
lm's avatar
lm committed
150

James Goppert's avatar
James Goppert committed
151 152
// MESSAGE WATCHDOG_COMMAND UNPACKING

lm's avatar
lm committed
153

James Goppert's avatar
James Goppert committed
154 155 156 157 158 159 160
/**
 * @brief Get field target_system_id from watchdog_command message
 *
 * @return Target system ID
 */
static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg)
{
LM's avatar
LM committed
161
	return _MAV_RETURN_uint8_t(msg,  4);
James Goppert's avatar
James Goppert committed
162 163 164 165 166 167 168 169 170
}

/**
 * @brief Get field watchdog_id from watchdog_command message
 *
 * @return Watchdog ID
 */
static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg)
{
LM's avatar
LM committed
171
	return _MAV_RETURN_uint16_t(msg,  0);
James Goppert's avatar
James Goppert committed
172 173 174 175 176 177 178 179 180
}

/**
 * @brief Get field process_id from watchdog_command message
 *
 * @return Process ID
 */
static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg)
{
LM's avatar
LM committed
181
	return _MAV_RETURN_uint16_t(msg,  2);
James Goppert's avatar
James Goppert committed
182 183 184 185 186 187 188 189 190
}

/**
 * @brief Get field command_id from watchdog_command message
 *
 * @return Command ID
 */
static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg)
{
LM's avatar
LM committed
191
	return _MAV_RETURN_uint8_t(msg,  5);
James Goppert's avatar
James Goppert committed
192 193 194 195 196 197 198 199 200 201
}

/**
 * @brief Decode a watchdog_command message into a struct
 *
 * @param msg The message to decode
 * @param watchdog_command C-struct to decode the message contents into
 */
static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command)
{
lm's avatar
lm committed
202 203 204 205 206 207
#if MAVLINK_NEED_BYTE_SWAP
	watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg);
	watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg);
	watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg);
	watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg);
#else
LM's avatar
LM committed
208
	memcpy(watchdog_command, _MAV_PAYLOAD(msg), 6);
lm's avatar
lm committed
209
#endif
James Goppert's avatar
James Goppert committed
210
}