Commit 8fef3ca0 authored by lm's avatar lm

Updated embedded MAVLink

parent 26122dca
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Thursday, August 11 2011, 07:25 UTC
* Generated on Friday, August 12 2011, 20:25 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......@@ -11,7 +11,7 @@ extern "C" {
#endif
#include "../protocol.h"
#include "../mavlink_protocol.h"
#define MAVLINK_ENABLED_COMMON
......@@ -273,12 +273,10 @@ enum MAV_CMD
#include "./mavlink_msg_control_status.h"
#include "./mavlink_msg_safety_set_allowed_area.h"
#include "./mavlink_msg_safety_allowed_area.h"
#include "./mavlink_msg_set_roll_pitch_yaw.h"
#include "./mavlink_msg_set_roll_pitch_yaw_speed.h"
#include "./mavlink_msg_roll_pitch_yaw_setpoint.h"
#include "./mavlink_msg_roll_pitch_yaw_speed_setpoint.h"
#include "./mavlink_msg_attitude_controller_output.h"
#include "./mavlink_msg_position_controller_output.h"
#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h"
#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h"
#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h"
#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h"
#include "./mavlink_msg_nav_controller_output.h"
#include "./mavlink_msg_position_target.h"
#include "./mavlink_msg_state_correction.h"
......@@ -302,7 +300,12 @@ enum MAV_CMD
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 44, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 79, 252, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 212, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 138, 43, 141, 211, 144 }
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 161, 116, 56, 245, 0, 0, 0, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 212, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 138, 43, 141, 211, 144 }
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 0, 2, 2, 0, 0, 0, 0, 0, 0, 0, 20, 2, 24, 22, 0, 30, 26, 101, 26, 16, 32, 32, 38, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 20, 20, 0, 0, 0, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 20, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 14, 14, 51 }
#ifdef __cplusplus
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, August 11 2011, 07:25 UTC
* Generated on Friday, August 12 2011, 20:25 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -3,16 +3,18 @@
#define MAVLINK_MSG_ID_ATTITUDE 30
#define MAVLINK_MSG_ID_ATTITUDE_LEN 32
#define MAVLINK_MSG_30_LEN 32
#define MAVLINK_MSG_ID_ATTITUDE_KEY 0xF3
#define MAVLINK_MSG_30_KEY 0xF3
typedef struct __mavlink_attitude_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
} mavlink_attitude_t;
......@@ -36,13 +38,13 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
mavlink_attitude_t *p = (mavlink_attitude_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
p->roll = roll; // float:Roll angle (rad)
p->pitch = pitch; // float:Pitch angle (rad)
p->yaw = yaw; // float:Yaw angle (rad)
p->rollspeed = rollspeed; // float:Roll angular speed (rad/s)
p->pitchspeed = pitchspeed; // float:Pitch angular speed (rad/s)
p->yawspeed = yawspeed; // float:Yaw angular speed (rad/s)
p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
p->roll = roll; // float:Roll angle (rad)
p->pitch = pitch; // float:Pitch angle (rad)
p->yaw = yaw; // float:Yaw angle (rad)
p->rollspeed = rollspeed; // float:Roll angular speed (rad/s)
p->pitchspeed = pitchspeed; // float:Pitch angular speed (rad/s)
p->yawspeed = yawspeed; // float:Yaw angular speed (rad/s)
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN);
}
......@@ -67,13 +69,13 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t
mavlink_attitude_t *p = (mavlink_attitude_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
p->roll = roll; // float:Roll angle (rad)
p->pitch = pitch; // float:Pitch angle (rad)
p->yaw = yaw; // float:Yaw angle (rad)
p->rollspeed = rollspeed; // float:Roll angular speed (rad/s)
p->pitchspeed = pitchspeed; // float:Pitch angular speed (rad/s)
p->yawspeed = yawspeed; // float:Yaw angular speed (rad/s)
p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
p->roll = roll; // float:Roll angle (rad)
p->pitch = pitch; // float:Pitch angle (rad)
p->yaw = yaw; // float:Yaw angle (rad)
p->rollspeed = rollspeed; // float:Roll angular speed (rad/s)
p->pitchspeed = pitchspeed; // float:Pitch angular speed (rad/s)
p->yawspeed = yawspeed; // float:Yaw angular speed (rad/s)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN);
}
......@@ -91,6 +93,8 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->usec, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
......@@ -103,23 +107,19 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{
mavlink_header_t hdr;
mavlink_attitude_t payload;
uint16_t checksum;
mavlink_attitude_t *p = &payload;
p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
p->roll = roll; // float:Roll angle (rad)
p->pitch = pitch; // float:Pitch angle (rad)
p->yaw = yaw; // float:Yaw angle (rad)
p->rollspeed = rollspeed; // float:Roll angular speed (rad/s)
p->pitchspeed = pitchspeed; // float:Pitch angular speed (rad/s)
p->yawspeed = yawspeed; // float:Yaw angular speed (rad/s)
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_ATTITUDE_LEN )
payload.usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
payload.roll = roll; // float:Roll angle (rad)
payload.pitch = pitch; // float:Pitch angle (rad)
payload.yaw = yaw; // float:Yaw angle (rad)
payload.rollspeed = rollspeed; // float:Roll angular speed (rad/s)
payload.pitchspeed = pitchspeed; // float:Pitch angular speed (rad/s)
payload.yawspeed = yawspeed; // float:Yaw angular speed (rad/s)
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_ATTITUDE_LEN;
......@@ -130,14 +130,12 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t us
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);
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0xF3, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
}
#endif
......
......@@ -3,10 +3,12 @@
#define MAVLINK_MSG_ID_AUTH_KEY 7
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
#define MAVLINK_MSG_7_LEN 32
#define MAVLINK_MSG_ID_AUTH_KEY_KEY 0xBA
#define MAVLINK_MSG_7_KEY 0xBA
typedef struct __mavlink_auth_key_t
{
char key[32]; ///< key
char key[32]; ///< key
} mavlink_auth_key_t;
#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
......@@ -25,7 +27,7 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp
mavlink_auth_key_t *p = (mavlink_auth_key_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN);
}
......@@ -44,7 +46,7 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t
mavlink_auth_key_t *p = (mavlink_auth_key_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN);
}
......@@ -62,23 +64,21 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co
return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a auth_key message
* @param chan MAVLink channel to send the message
*
* @param key key
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char* key)
{
mavlink_header_t hdr;
mavlink_auth_key_t payload;
uint16_t checksum;
mavlink_auth_key_t *p = &payload;
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_AUTH_KEY_LEN )
memcpy(payload.key, key, sizeof(payload.key)); // char[32]:key
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_AUTH_KEY_LEN;
......@@ -89,14 +89,12 @@ static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char*
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);
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0xBA, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
}
#endif
......
......@@ -3,10 +3,12 @@
#define MAVLINK_MSG_ID_BOOT 1
#define MAVLINK_MSG_ID_BOOT_LEN 4
#define MAVLINK_MSG_1_LEN 4
#define MAVLINK_MSG_ID_BOOT_KEY 0xF9
#define MAVLINK_MSG_1_KEY 0xF9
typedef struct __mavlink_boot_t
{
uint32_t version; ///< The onboard software version
uint32_t version; ///< The onboard software version
} mavlink_boot_t;
......@@ -24,7 +26,7 @@ static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t componen
mavlink_boot_t *p = (mavlink_boot_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_BOOT;
p->version = version; // uint32_t:The onboard software version
p->version = version; // uint32_t:The onboard software version
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BOOT_LEN);
}
......@@ -43,7 +45,7 @@ static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t com
mavlink_boot_t *p = (mavlink_boot_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_BOOT;
p->version = version; // uint32_t:The onboard software version
p->version = version; // uint32_t:The onboard software version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BOOT_LEN);
}
......@@ -61,23 +63,21 @@ static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t compon
return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a boot message
* @param chan MAVLink channel to send the message
*
* @param version The onboard software version
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
{
mavlink_header_t hdr;
mavlink_boot_t payload;
uint16_t checksum;
mavlink_boot_t *p = &payload;
p->version = version; // uint32_t:The onboard software version
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_BOOT_LEN )
payload.version = version; // uint32_t:The onboard software version
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_BOOT_LEN;
......@@ -88,14 +88,12 @@ static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t versio
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);
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0xF9, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
}
#endif
......
......@@ -3,13 +3,15 @@
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
#define MAVLINK_MSG_5_LEN 28
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_KEY 0x7E
#define MAVLINK_MSG_5_KEY 0x7E
typedef struct __mavlink_change_operator_control_t
{
uint8_t target_system; ///< System the GCS requests control for
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
uint8_t target_system; ///< System the GCS requests control for
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
} mavlink_change_operator_control_t;
#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
......@@ -31,10 +33,10 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i
mavlink_change_operator_control_t *p = (mavlink_change_operator_control_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
p->target_system = target_system; // uint8_t:System the GCS requests control for
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->version = version; // uint8_t:0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
memcpy(p->passkey, passkey, sizeof(p->passkey)); // char[25]:Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
p->target_system = target_system; // uint8_t:System the GCS requests control for
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->version = version; // uint8_t:0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
memcpy(p->passkey, passkey, sizeof(p->passkey)); // char[25]:Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
}
......@@ -56,10 +58,10 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys
mavlink_change_operator_control_t *p = (mavlink_change_operator_control_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
p->target_system = target_system; // uint8_t:System the GCS requests control for
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->version = version; // uint8_t:0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
memcpy(p->passkey, passkey, sizeof(p->passkey)); // char[25]:Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
p->target_system = target_system; // uint8_t:System the GCS requests control for
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->version = version; // uint8_t:0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
memcpy(p->passkey, passkey, sizeof(p->passkey)); // char[25]:Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
}
......@@ -77,6 +79,8 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system
return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a change_operator_control message
* @param chan MAVLink channel to send the message
......@@ -86,20 +90,16 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey)
{
mavlink_header_t hdr;
mavlink_change_operator_control_t payload;
uint16_t checksum;
mavlink_change_operator_control_t *p = &payload;
p->target_system = target_system; // uint8_t:System the GCS requests control for
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->version = version; // uint8_t:0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
memcpy(p->passkey, passkey, sizeof(p->passkey)); // char[25]:Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN )
payload.target_system = target_system; // uint8_t:System the GCS requests control for
payload.control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
payload.version = version; // uint8_t:0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
memcpy(payload.passkey, passkey, sizeof(payload.passkey)); // char[25]:Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN;
......@@ -110,14 +110,12 @@ static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t ch
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);
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x7E, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
}
#endif
......
......@@ -3,12 +3,14 @@
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3
#define MAVLINK_MSG_6_LEN 3
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_KEY 0x75
#define MAVLINK_MSG_6_KEY 0x75
typedef struct __mavlink_change_operator_control_ack_t
{
uint8_t gcs_system_id; ///< ID of the GCS this message
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
uint8_t gcs_system_id; ///< ID of the GCS this message
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
} mavlink_change_operator_control_ack_t;
......@@ -28,9 +30,9 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t syst
mavlink_change_operator_control_ack_t *p = (mavlink_change_operator_control_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
p->gcs_system_id = gcs_system_id; // uint8_t:ID of the GCS this message
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->ack = ack; // uint8_t:0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
p->gcs_system_id = gcs_system_id; // uint8_t:ID of the GCS this message
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->ack = ack; // uint8_t:0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
}
......@@ -51,9 +53,9 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t
mavlink_change_operator_control_ack_t *p = (mavlink_change_operator_control_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
p->gcs_system_id = gcs_system_id; // uint8_t:ID of the GCS this message
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->ack = ack; // uint8_t:0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
p->gcs_system_id = gcs_system_id; // uint8_t:ID of the GCS this message
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->ack = ack; // uint8_t:0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
}
......@@ -71,6 +73,8 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy
return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a change_operator_control_ack message
* @param chan MAVLink channel to send the message
......@@ -79,19 +83,15 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
mavlink_header_t hdr;
mavlink_change_operator_control_ack_t payload;
uint16_t checksum;
mavlink_change_operator_control_ack_t *p = &payload;
p->gcs_system_id = gcs_system_id; // uint8_t:ID of the GCS this message
p->control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
p->ack = ack; // uint8_t:0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN )
payload.gcs_system_id = gcs_system_id; // uint8_t:ID of the GCS this message
payload.control_request = control_request; // uint8_t:0: request control of this MAV, 1: Release control of this MAV
payload.ack = ack; // uint8_t:0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN;
......@@ -102,14 +102,12 @@ static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_
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);
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x75, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
}
#endif
......
......@@ -3,11 +3,13 @@
#define MAVLINK_MSG_ID_CMD_ACK 9
#define MAVLINK_MSG_ID_CMD_ACK_LEN 2
#define MAVLINK_MSG_9_LEN 2
#define MAVLINK_MSG_ID_CMD_ACK_KEY 0x90
#define MAVLINK_MSG_9_KEY 0x90
typedef struct __mavlink_cmd_ack_t
{
uint8_t cmd; ///< The MAV_CMD ID
uint8_t result; ///< 0: Action DENIED, 1: Action executed
uint8_t cmd; ///< The MAV_CMD ID
uint8_t result; ///< 0: Action DENIED, 1: Action executed
} mavlink_cmd_ack_t;
......@@ -26,8 +28,8 @@ static inline uint16_t mavlink_msg_cmd_ack_pack(uint8_t system_id, uint8_t compo
mavlink_cmd_ack_t *p = (mavlink_cmd_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CMD_ACK;
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_ACK_LEN);
}
......@@ -47,8 +49,8 @@ static inline uint16_t mavlink_msg_cmd_ack_pack_chan(uint8_t system_id, uint8_t
mavlink_cmd_ack_t *p = (mavlink_cmd_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CMD_ACK;
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_ACK_LEN);
}
......@@ -66,6 +68,8 @@ static inline uint16_t mavlink_msg_cmd_ack_encode(uint8_t system_id, uint8_t com
return mavlink_msg_cmd_ack_pack(system_id, component_id, msg, cmd_ack->cmd, cmd_ack->result);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a cmd_ack message
* @param chan MAVLink channel to send the message
......@@ -73,18 +77,14 @@ static inline uint16_t mavlink_msg_cmd_ack_encode(uint8_t system_id, uint8_t com
* @param cmd The MAV_CMD ID
* @param result 0: Action DENIED, 1: Action executed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cmd_ack_send(mavlink_channel_t chan, uint8_t cmd, uint8_t result)
{
mavlink_header_t hdr;
mavlink_cmd_ack_t payload;
uint16_t checksum;
mavlink_cmd_ack_t *p = &payload;
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_CMD_ACK_LEN )
payload.cmd = cmd; // uint8_t:The MAV_CMD ID
payload.result = result; // uint8_t:0: Action DENIED, 1: Action executed
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_CMD_ACK_LEN;
......@@ -95,14 +95,12 @@ static inline void mavlink_msg_cmd_ack_send(mavlink_channel_t chan, uint8_t cmd,
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);
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x90, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
}
#endif
......
......@@ -3,17 +3,19 @@
#define MAVLINK_MSG_ID_COMMAND 75
#define MAVLINK_MSG_ID_COMMAND_LEN 20
#define MAVLINK_MSG_75_LEN 20
#define MAVLINK_MSG_ID_COMMAND_KEY 0x14
#define MAVLINK_MSG_75_KEY 0x14
typedef struct __mavlink_command_t
{
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.
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.
uint8_t target_system; ///< System which should execute the command