mavlink_msg_command.h 12.2 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE COMMAND PACKING

#define MAVLINK_MSG_ID_COMMAND 75
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_COMMAND_LEN 20
#define MAVLINK_MSG_75_LEN 20
James Goppert's avatar
James Goppert committed
6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37

typedef struct __mavlink_command_t 
{
	uint8_t target_system; ///< System which should execute the command
	uint8_t target_component; ///< Component which should execute the command, 0 for all components
	uint8_t command; ///< Command ID, as defined by MAV_CMD enum.
	uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
	float param1; ///< Parameter 1, as defined by MAV_CMD enum.
	float param2; ///< Parameter 2, as defined by MAV_CMD enum.
	float param3; ///< Parameter 3, as defined by MAV_CMD enum.
	float param4; ///< Parameter 4, as defined by MAV_CMD enum.

} mavlink_command_t;

/**
 * @brief Pack a 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 System which should execute the command
 * @param target_component Component which should execute the command, 0 for all components
 * @param command Command ID, as defined by MAV_CMD enum.
 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
 * @param param1 Parameter 1, as defined by MAV_CMD enum.
 * @param param2 Parameter 2, as defined by MAV_CMD enum.
 * @param param3 Parameter 3, as defined by MAV_CMD enum.
 * @param param4 Parameter 4, as defined by MAV_CMD enum.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{
lm's avatar
lm committed
38
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
39 40
	msg->msgid = MAVLINK_MSG_ID_COMMAND;

lm's avatar
lm committed
41 42 43 44 45 46 47 48
	p->target_system = target_system; // uint8_t:System which should execute the command
	p->target_component = target_component; // uint8_t:Component which should execute the command, 0 for all components
	p->command = command; // uint8_t:Command ID, as defined by MAV_CMD enum.
	p->confirmation = confirmation; // uint8_t:0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
	p->param1 = param1; // float:Parameter 1, as defined by MAV_CMD enum.
	p->param2 = param2; // float:Parameter 2, as defined by MAV_CMD enum.
	p->param3 = param3; // float:Parameter 3, as defined by MAV_CMD enum.
	p->param4 = param4; // float:Parameter 4, as defined by MAV_CMD enum.
James Goppert's avatar
James Goppert committed
49

lm's avatar
lm committed
50
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LEN);
James Goppert's avatar
James Goppert committed
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70
}

/**
 * @brief Pack a command message
 * @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 System which should execute the command
 * @param target_component Component which should execute the command, 0 for all components
 * @param command Command ID, as defined by MAV_CMD enum.
 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
 * @param param1 Parameter 1, as defined by MAV_CMD enum.
 * @param param2 Parameter 2, as defined by MAV_CMD enum.
 * @param param3 Parameter 3, as defined by MAV_CMD enum.
 * @param param4 Parameter 4, as defined by MAV_CMD enum.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{
lm's avatar
lm committed
71
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
72 73
	msg->msgid = MAVLINK_MSG_ID_COMMAND;

lm's avatar
lm committed
74 75 76 77 78 79 80 81
	p->target_system = target_system; // uint8_t:System which should execute the command
	p->target_component = target_component; // uint8_t:Component which should execute the command, 0 for all components
	p->command = command; // uint8_t:Command ID, as defined by MAV_CMD enum.
	p->confirmation = confirmation; // uint8_t:0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
	p->param1 = param1; // float:Parameter 1, as defined by MAV_CMD enum.
	p->param2 = param2; // float:Parameter 2, as defined by MAV_CMD enum.
	p->param3 = param3; // float:Parameter 3, as defined by MAV_CMD enum.
	p->param4 = param4; // float:Parameter 4, as defined by MAV_CMD enum.
James Goppert's avatar
James Goppert committed
82

lm's avatar
lm committed
83
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LEN);
James Goppert's avatar
James Goppert committed
84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115
}

/**
 * @brief Encode a 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 command C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_t* command)
{
	return mavlink_msg_command_pack(system_id, component_id, msg, command->target_system, command->target_component, command->command, command->confirmation, command->param1, command->param2, command->param3, command->param4);
}

/**
 * @brief Send a command message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System which should execute the command
 * @param target_component Component which should execute the command, 0 for all components
 * @param command Command ID, as defined by MAV_CMD enum.
 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
 * @param param1 Parameter 1, as defined by MAV_CMD enum.
 * @param param2 Parameter 2, as defined by MAV_CMD enum.
 * @param param3 Parameter 3, as defined by MAV_CMD enum.
 * @param param4 Parameter 4, as defined by MAV_CMD enum.
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{
	mavlink_message_t msg;
lm's avatar
lm committed
116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177
	uint16_t checksum;
	mavlink_command_t *p = (mavlink_command_t *)&msg.payload[0];

	p->target_system = target_system; // uint8_t:System which should execute the command
	p->target_component = target_component; // uint8_t:Component which should execute the command, 0 for all components
	p->command = command; // uint8_t:Command ID, as defined by MAV_CMD enum.
	p->confirmation = confirmation; // uint8_t:0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
	p->param1 = param1; // float:Parameter 1, as defined by MAV_CMD enum.
	p->param2 = param2; // float:Parameter 2, as defined by MAV_CMD enum.
	p->param3 = param3; // float:Parameter 3, as defined by MAV_CMD enum.
	p->param4 = param4; // float:Parameter 4, as defined by MAV_CMD enum.

	msg.STX = MAVLINK_STX;
	msg.len = MAVLINK_MSG_ID_COMMAND_LEN;
	msg.msgid = MAVLINK_MSG_ID_COMMAND;
	msg.sysid = mavlink_system.sysid;
	msg.compid = mavlink_system.compid;
	msg.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = msg.seq + 1;
	checksum = crc_calculate_msg(&msg, msg.len + MAVLINK_CORE_HEADER_LEN);
	msg.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	msg.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_msg(chan, &msg);
}

#endif

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS_SMALL
static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{
	mavlink_header_t hdr;
	mavlink_command_t payload;
	uint16_t checksum;
	mavlink_command_t *p = &payload;

	p->target_system = target_system; // uint8_t:System which should execute the command
	p->target_component = target_component; // uint8_t:Component which should execute the command, 0 for all components
	p->command = command; // uint8_t:Command ID, as defined by MAV_CMD enum.
	p->confirmation = confirmation; // uint8_t:0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
	p->param1 = param1; // float:Parameter 1, as defined by MAV_CMD enum.
	p->param2 = param2; // float:Parameter 2, as defined by MAV_CMD enum.
	p->param3 = param3; // float:Parameter 3, as defined by MAV_CMD enum.
	p->param4 = param4; // float:Parameter 4, as defined by MAV_CMD enum.

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_COMMAND_LEN;
	hdr.msgid = MAVLINK_MSG_ID_COMMAND;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
178 179 180 181 182 183 184 185 186 187 188 189
}

#endif
// MESSAGE COMMAND UNPACKING

/**
 * @brief Get field target_system from command message
 *
 * @return System which should execute the command
 */
static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg)
{
lm's avatar
lm committed
190 191
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (uint8_t)(p->target_system);
James Goppert's avatar
James Goppert committed
192 193 194 195 196 197 198 199 200
}

/**
 * @brief Get field target_component from command message
 *
 * @return Component which should execute the command, 0 for all components
 */
static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg)
{
lm's avatar
lm committed
201 202
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (uint8_t)(p->target_component);
James Goppert's avatar
James Goppert committed
203 204 205 206 207 208 209 210 211
}

/**
 * @brief Get field command from command message
 *
 * @return Command ID, as defined by MAV_CMD enum.
 */
static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg)
{
lm's avatar
lm committed
212 213
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (uint8_t)(p->command);
James Goppert's avatar
James Goppert committed
214 215 216 217 218 219 220 221 222
}

/**
 * @brief Get field confirmation from command message
 *
 * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
 */
static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg)
{
lm's avatar
lm committed
223 224
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (uint8_t)(p->confirmation);
James Goppert's avatar
James Goppert committed
225 226 227 228 229 230 231 232 233
}

/**
 * @brief Get field param1 from command message
 *
 * @return Parameter 1, as defined by MAV_CMD enum.
 */
static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg)
{
lm's avatar
lm committed
234 235
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (float)(p->param1);
James Goppert's avatar
James Goppert committed
236 237 238 239 240 241 242 243 244
}

/**
 * @brief Get field param2 from command message
 *
 * @return Parameter 2, as defined by MAV_CMD enum.
 */
static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg)
{
lm's avatar
lm committed
245 246
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (float)(p->param2);
James Goppert's avatar
James Goppert committed
247 248 249 250 251 252 253 254 255
}

/**
 * @brief Get field param3 from command message
 *
 * @return Parameter 3, as defined by MAV_CMD enum.
 */
static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg)
{
lm's avatar
lm committed
256 257
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (float)(p->param3);
James Goppert's avatar
James Goppert committed
258 259 260 261 262 263 264 265 266
}

/**
 * @brief Get field param4 from command message
 *
 * @return Parameter 4, as defined by MAV_CMD enum.
 */
static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg)
{
lm's avatar
lm committed
267 268
	mavlink_command_t *p = (mavlink_command_t *)&msg->payload[0];
	return (float)(p->param4);
James Goppert's avatar
James Goppert committed
269 270 271 272 273 274 275 276 277 278
}

/**
 * @brief Decode a command message into a struct
 *
 * @param msg The message to decode
 * @param command C-struct to decode the message contents into
 */
static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command)
{
lm's avatar
lm committed
279
	memcpy( command, msg->payload, sizeof(mavlink_command_t));
James Goppert's avatar
James Goppert committed
280
}