Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_change_operator_control.h Source File

mavlink_msg_change_operator_control.h

00001 // MESSAGE CHANGE_OPERATOR_CONTROL PACKING
00002 
00003 #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
00004 
00005 typedef struct __mavlink_change_operator_control_t 
00006 {
00007     uint8_t target_system; ///< System the GCS requests control for
00008     uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
00009     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.
00010     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 "!?,.-"
00011 
00012 } mavlink_change_operator_control_t;
00013 
00014 #define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
00015 
00016 
00017 /**
00018  * @brief Pack a change_operator_control message
00019  * @param system_id ID of this system
00020  * @param component_id ID of this component (e.g. 200 for IMU)
00021  * @param msg The MAVLink message to compress the data into
00022  *
00023  * @param target_system System the GCS requests control for
00024  * @param control_request 0: request control of this MAV, 1: Release control of this MAV
00025  * @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.
00026  * @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 "!?,.-"
00027  * @return length of the message in bytes (excluding serial stream start sign)
00028  */
00029 static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey)
00030 {
00031     uint16_t i = 0;
00032     msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
00033 
00034     i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for
00035     i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
00036     i += put_uint8_t_by_index(version, i, msg->payload); // 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.
00037     i += put_array_by_index((const int8_t*)passkey, sizeof(char)*25, i, msg->payload); // 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 "!?,.-"
00038 
00039     return mavlink_finalize_message(msg, system_id, component_id, i);
00040 }
00041 
00042 /**
00043  * @brief Pack a change_operator_control message
00044  * @param system_id ID of this system
00045  * @param component_id ID of this component (e.g. 200 for IMU)
00046  * @param chan The MAVLink channel this message was sent over
00047  * @param msg The MAVLink message to compress the data into
00048  * @param target_system System the GCS requests control for
00049  * @param control_request 0: request control of this MAV, 1: Release control of this MAV
00050  * @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.
00051  * @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 "!?,.-"
00052  * @return length of the message in bytes (excluding serial stream start sign)
00053  */
00054 static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey)
00055 {
00056     uint16_t i = 0;
00057     msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
00058 
00059     i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for
00060     i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
00061     i += put_uint8_t_by_index(version, i, msg->payload); // 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.
00062     i += put_array_by_index((const int8_t*)passkey, sizeof(char)*25, i, msg->payload); // 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 "!?,.-"
00063 
00064     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00065 }
00066 
00067 /**
00068  * @brief Encode a change_operator_control struct into a message
00069  *
00070  * @param system_id ID of this system
00071  * @param component_id ID of this component (e.g. 200 for IMU)
00072  * @param msg The MAVLink message to compress the data into
00073  * @param change_operator_control C-struct to read the message contents from
00074  */
00075 static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
00076 {
00077     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);
00078 }
00079 
00080 /**
00081  * @brief Send a change_operator_control message
00082  * @param chan MAVLink channel to send the message
00083  *
00084  * @param target_system System the GCS requests control for
00085  * @param control_request 0: request control of this MAV, 1: Release control of this MAV
00086  * @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.
00087  * @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 "!?,.-"
00088  */
00089 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00090 
00091 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)
00092 {
00093     mavlink_message_t msg;
00094     mavlink_msg_change_operator_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, control_request, version, passkey);
00095     mavlink_send_uart(chan, &msg);
00096 }
00097 
00098 #endif
00099 // MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
00100 
00101 /**
00102  * @brief Get field target_system from change_operator_control message
00103  *
00104  * @return System the GCS requests control for
00105  */
00106 static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
00107 {
00108     return (uint8_t)(msg->payload)[0];
00109 }
00110 
00111 /**
00112  * @brief Get field control_request from change_operator_control message
00113  *
00114  * @return 0: request control of this MAV, 1: Release control of this MAV
00115  */
00116 static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
00117 {
00118     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00119 }
00120 
00121 /**
00122  * @brief Get field version from change_operator_control message
00123  *
00124  * @return 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.
00125  */
00126 static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
00127 {
00128     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00129 }
00130 
00131 /**
00132  * @brief Get field passkey from change_operator_control message
00133  *
00134  * @return 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 "!?,.-"
00135  */
00136 static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char* r_data)
00137 {
00138 
00139     memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t), sizeof(char)*25);
00140     return sizeof(char)*25;
00141 }
00142 
00143 /**
00144  * @brief Decode a change_operator_control message into a struct
00145  *
00146  * @param msg The message to decode
00147  * @param change_operator_control C-struct to decode the message contents into
00148  */
00149 static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
00150 {
00151     change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
00152     change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
00153     change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
00154     mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
00155 }