Mavlink update.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1685 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2011-02-19 17:54:14 +00:00
parent b268578975
commit 4c79a2c9a5
18 changed files with 579 additions and 98 deletions

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, December 2 2010, 10:44 UTC
* Generated on Tuesday, February 15 2011, 15:57 UTC
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
@ -17,6 +17,17 @@ extern "C" {
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, December 2 2010, 10:44 UTC
* Generated on Tuesday, February 15 2011, 15:57 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, February 11 2011, 07:42 UTC
* Generated on Wednesday, February 16 2011, 19:40 UTC
*/
#ifndef COMMON_H
#define COMMON_H
@ -31,29 +31,27 @@ extern "C" {
/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. */
enum MAV_CMD
{
MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint.Hold time (ignored by fixed wing, time to stay at waypoint for rotary wing)Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)0 to pass through the WP, if > 0 radius to pass by WP. Allows trajectory control.Desired yaw angleLatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of timeEmptyEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turnsTurnsEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X secondsSeconds (decimal)EmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint.Hold time (ignored by fixed wing, time to stay at waypoint for rotary wing)Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)0 to pass through the WP, if > 0 radius to pass by WP. Allows trajectory control.Desired yaw angleLatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of timeEmptyEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turnsTurnsEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X secondsSeconds (decimal)EmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch locationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_NAV_LAND=21, /* Land at locationEmptyEmptyEmptyDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / handMinimum pitch (if airspeed sensor present), desired pitch without sensorEmptyEmptyYaw angle (if magnetometer present), ignored without magnetometerLatitudeLongitudeAltitude*/
MAV_CMD_NAV_R_WAYPOINT=23, /* Navigate to waypoint.Hold time (ignored by fixed wing, time to stay at waypoint for rotary wing)Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)0 to pass through the WP, if > 0 radius to pass by WP. Allows trajectory control.Desired yaw angleLatitudeLongitudeAltitude*/
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine.Delay in seconds (decimal)EmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_NAV_LAND=21, /* Land at locationEmptyEmptyEmptyDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / handMinimum pitch (if airspeed sensor present), desired pitch without sensorEmptyEmptyYaw angle (if magnetometer present), ignored without magnetometerLatitudeLongitudeAltitude*/
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine.Delay in seconds (decimal)EmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached.Descent / Ascend rate (m/s)EmptyEmptyEmptyEmptyEmptyFinish Altitude*/
MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point.Distance (meters)EmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_ANGLE=160, /* */
MAV_CMD_DO_SET_MODE=176, /* Set system mode.Mode, as defined by ENUM MAV_MODEEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of timesSequence numberRepeat countEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points.Speed type (0=Airspeed, 1=Ground Speed)Speed (m/s, -1 indicates no change)Throttle ( Percent, -1 indicates no change)EmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location.Use current (1=use current location, 0=use specified location)EmptyEmptyEmptyLatitudeLongitudeAltitude*/
MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.Parameter numberParameter valueEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition.Relay numberSetting (1=on, 0=off, others possible depending on system hardware)EmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period.Relay numberCycle countCycle time (seconds, decimal)EmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value.Servo numberPWM (microseconds, 1000 to 2000 typical)EmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cyles with a desired period.Servo numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/
MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_MODE=176, /* Set system mode.Mode, as defined by ENUM MAV_MODEEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of timesSequence numberRepeat countEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points.Speed type (0=Airspeed, 1=Ground Speed)Speed (m/s, -1 indicates no change)Throttle ( Percent, -1 indicates no change)EmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location.Use current (1=use current location, 0=use specified location)EmptyEmptyEmptyLatitudeLongitudeAltitude*/
MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.Parameter numberParameter valueEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition.Relay numberSetting (1=on, 0=off, others possible depending on system hardware)EmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period.Relay numberCycle countCycle time (seconds, decimal)EmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value.Servo numberPWM (microseconds, 1000 to 2000 typical)EmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cyles with a desired period.Servo numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/
MAV_CMD_ENUM_END
};
@ -66,9 +64,9 @@ enum MAV_DATA_STREAM
MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW*/
MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.*/
MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.*/
MAV_DATA_STREAM_EXTRA1=250, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA2=251, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA3=252, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot*/
MAV_DATA_STREAM_ENUM_END
};
@ -80,6 +78,8 @@ enum MAV_DATA_STREAM
#include "./mavlink_msg_system_time.h"
#include "./mavlink_msg_ping.h"
#include "./mavlink_msg_system_time_utc.h"
#include "./mavlink_msg_change_operator_control.h"
#include "./mavlink_msg_change_operator_control_ack.h"
#include "./mavlink_msg_action_ack.h"
#include "./mavlink_msg_action.h"
#include "./mavlink_msg_set_mode.h"

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, February 11 2011, 07:42 UTC
* Generated on Wednesday, February 16 2011, 19:40 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -0,0 +1,155 @@
// MESSAGE CHANGE_OPERATOR_CONTROL PACKING
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
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 "!?,.-"
} mavlink_change_operator_control_t;
#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
/**
* @brief Pack a change_operator_control 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 the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @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 "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
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)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for
i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
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.
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 "!?,.-"
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a change_operator_control 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 the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @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 "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
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)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for
i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
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.
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 "!?,.-"
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a change_operator_control 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 change_operator_control C-struct to read the message contents from
*/
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)
{
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);
}
/**
* @brief Send a change_operator_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @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_message_t msg;
mavlink_msg_change_operator_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, control_request, version, passkey);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
/**
* @brief Get field target_system from change_operator_control message
*
* @return System the GCS requests control for
*/
static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field control_request from change_operator_control message
*
* @return 0: request control of this MAV, 1: Release control of this MAV
*/
static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field version from change_operator_control message
*
* @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.
*/
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field passkey from change_operator_control message
*
* @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 "!?,.-"
*/
static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char* r_data)
{
memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t), sizeof(char)*25);
return sizeof(char)*25;
}
/**
* @brief Decode a change_operator_control message into a struct
*
* @param msg The message to decode
* @param change_operator_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
{
change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
}

View File

@ -0,0 +1,135 @@
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
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
} mavlink_change_operator_control_ack_t;
/**
* @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message
* @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
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
i += put_uint8_t_by_index(gcs_system_id, i, msg->payload); // ID of the GCS this message
i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
i += put_uint8_t_by_index(ack, i, msg->payload); // 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, i);
}
/**
* @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message
* @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
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
i += put_uint8_t_by_index(gcs_system_id, i, msg->payload); // ID of the GCS this message
i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV
i += put_uint8_t_by_index(ack, i, msg->payload); // 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, i);
}
/**
* @brief Encode a change_operator_control_ack 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 change_operator_control_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
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);
}
/**
* @brief Send a change_operator_control_ack message
* @param chan MAVLink channel to send the message
*
* @param gcs_system_id ID of the GCS this message
* @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_message_t msg;
mavlink_msg_change_operator_control_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, gcs_system_id, control_request, ack);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING
/**
* @brief Get field gcs_system_id from change_operator_control_ack message
*
* @return ID of the GCS this message
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field control_request from change_operator_control_ack message
*
* @return 0: request control of this MAV, 1: Release control of this MAV
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field ack from change_operator_control_ack message
*
* @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a change_operator_control_ack message into a struct
*
* @param msg The message to decode
* @param change_operator_control_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg);
change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg);
change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg);
}

View File

@ -5,7 +5,7 @@
typedef struct __mavlink_gps_raw_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
float lat; ///< Latitude in degrees
float lon; ///< Longitude in degrees
float alt; ///< Altitude in meters
@ -25,7 +25,7 @@ typedef struct __mavlink_gps_raw_t
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in degrees
* @param lon Longitude in degrees
* @param alt Altitude in meters
@ -41,7 +41,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
i += put_float_by_index(alt, i, msg->payload); // Altitude in meters
@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in degrees
* @param lon Longitude in degrees
* @param alt Altitude in meters
@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
i += put_float_by_index(alt, i, msg->payload); // Altitude in meters
@ -106,7 +106,7 @@ static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t com
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in degrees
* @param lon Longitude in degrees
* @param alt Altitude in meters
@ -149,7 +149,7 @@ static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg
/**
* @brief Get field fix_type from gps_raw message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
*/
static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg)
{

View File

@ -5,7 +5,7 @@
typedef struct __mavlink_gps_raw_int_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
int32_t lat; ///< Latitude in 1E7 degrees
int32_t lon; ///< Longitude in 1E7 degrees
int32_t alt; ///< Altitude in 1E3 meters (millimeters)
@ -25,7 +25,7 @@ typedef struct __mavlink_gps_raw_int_t
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
@ -41,7 +41,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters)
@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters)
@ -106,7 +106,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
@ -149,7 +149,7 @@ static inline uint64_t mavlink_msg_gps_raw_int_get_usec(const mavlink_message_t*
/**
* @brief Get field fix_type from gps_raw_int message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{

View File

@ -7,7 +7,7 @@ typedef struct __mavlink_param_request_read_t
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int8_t param_id[15]; ///< Onboard parameter id
uint16_t param_index; ///< Parameter index
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
} mavlink_param_request_read_t;
@ -23,10 +23,10 @@ typedef struct __mavlink_param_request_read_t
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, uint16_t param_index)
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
@ -34,7 +34,7 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_uint16_t_by_index(param_index, i, msg->payload); // Parameter index
i += put_int16_t_by_index(param_index, i, msg->payload); // Parameter index. Send -1 to use the param ID field as identifier
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -48,10 +48,10 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_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, const int8_t* param_id, uint16_t param_index)
static inline uint16_t mavlink_msg_param_request_read_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, const int8_t* param_id, int16_t param_index)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_i
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_uint16_t_by_index(param_index, i, msg->payload); // Parameter index
i += put_int16_t_by_index(param_index, i, msg->payload); // Parameter index. Send -1 to use the param ID field as identifier
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -84,11 +84,11 @@ static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id,
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, uint16_t param_index)
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index)
{
mavlink_message_t msg;
mavlink_msg_param_request_read_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_index);
@ -133,14 +133,14 @@ static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink
/**
* @brief Get field param_index from param_request_read message
*
* @return Parameter index
* @return Parameter index. Send -1 to use the param ID field as identifier
*/
static inline uint16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1];
return (uint16_t)r.s;
return (int16_t)r.s;
}
/**

View File

@ -92,7 +92,8 @@ enum MAV_NAV
MAV_NAV_VECTOR,
MAV_NAV_RETURNING,
MAV_NAV_LANDING,
MAV_NAV_LOST
MAV_NAV_LOST,
MAV_NAV_LOITER
};
enum MAV_TYPE

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, February 11 2011, 07:42 UTC
* Generated on Wednesday, February 16 2011, 19:40 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, February 11 2011, 07:42 UTC
* Generated on Wednesday, February 16 2011, 19:40 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Monday, October 25 2010, 17:38 UTC
* Generated on Tuesday, February 15 2011, 15:58 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_nav_filter_bias_t
/**
* @brief Send a nav_filter_bias message
* @brief Pack a nav_filter_bias 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 usec Timestamp (microseconds)
* @param accel_0 b_f[0]
@ -33,28 +36,79 @@ static inline uint16_t mavlink_msg_nav_filter_bias_pack(uint8_t system_id, uint8
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds)
i += put_float_by_index(accel_0, i, msg->payload); //b_f[0]
i += put_float_by_index(accel_1, i, msg->payload); //b_f[1]
i += put_float_by_index(accel_2, i, msg->payload); //b_f[2]
i += put_float_by_index(gyro_0, i, msg->payload); //b_f[0]
i += put_float_by_index(gyro_1, i, msg->payload); //b_f[1]
i += put_float_by_index(gyro_2, i, msg->payload); //b_f[2]
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
i += put_float_by_index(accel_0, i, msg->payload); // b_f[0]
i += put_float_by_index(accel_1, i, msg->payload); // b_f[1]
i += put_float_by_index(accel_2, i, msg->payload); // b_f[2]
i += put_float_by_index(gyro_0, i, msg->payload); // b_f[0]
i += put_float_by_index(gyro_1, i, msg->payload); // b_f[1]
i += put_float_by_index(gyro_2, i, msg->payload); // b_f[2]
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a nav_filter_bias 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 usec Timestamp (microseconds)
* @param accel_0 b_f[0]
* @param accel_1 b_f[1]
* @param accel_2 b_f[2]
* @param gyro_0 b_f[0]
* @param gyro_1 b_f[1]
* @param gyro_2 b_f[2]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_filter_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
i += put_float_by_index(accel_0, i, msg->payload); // b_f[0]
i += put_float_by_index(accel_1, i, msg->payload); // b_f[1]
i += put_float_by_index(accel_2, i, msg->payload); // b_f[2]
i += put_float_by_index(gyro_0, i, msg->payload); // b_f[0]
i += put_float_by_index(gyro_1, i, msg->payload); // b_f[1]
i += put_float_by_index(gyro_2, i, msg->payload); // b_f[2]
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a nav_filter_bias 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 nav_filter_bias C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_nav_filter_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_filter_bias_t* nav_filter_bias)
{
return mavlink_msg_nav_filter_bias_pack(system_id, component_id, msg, nav_filter_bias->usec, nav_filter_bias->accel_0, nav_filter_bias->accel_1, nav_filter_bias->accel_2, nav_filter_bias->gyro_0, nav_filter_bias->gyro_1, nav_filter_bias->gyro_2);
}
/**
* @brief Send a nav_filter_bias message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds)
* @param accel_0 b_f[0]
* @param accel_1 b_f[1]
* @param accel_2 b_f[2]
* @param gyro_0 b_f[0]
* @param gyro_1 b_f[1]
* @param gyro_2 b_f[2]
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_nav_filter_bias_send(mavlink_channel_t chan, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2)
{
mavlink_message_t msg;
mavlink_msg_nav_filter_bias_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, accel_0, accel_1, accel_2, gyro_0, gyro_1, gyro_2);
mavlink_msg_nav_filter_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, accel_0, accel_1, accel_2, gyro_0, gyro_1, gyro_2);
mavlink_send_uart(chan, &msg);
}
@ -170,6 +224,12 @@ static inline float mavlink_msg_nav_filter_bias_get_gyro_2(const mavlink_message
return (float)r.f;
}
/**
* @brief Decode a nav_filter_bias message into a struct
*
* @param msg The message to decode
* @param nav_filter_bias C-struct to decode the message contents into
*/
static inline void mavlink_msg_nav_filter_bias_decode(const mavlink_message_t* msg, mavlink_nav_filter_bias_t* nav_filter_bias)
{
nav_filter_bias->usec = mavlink_msg_nav_filter_bias_get_usec(msg);

View File

@ -1,6 +1,6 @@
// MESSAGE RADIO_CALIBRATION PACKING
#define MAVLINK_MSG_ID_RADIO_CALIBRATION 82
#define MAVLINK_MSG_ID_RADIO_CALIBRATION 222
typedef struct __mavlink_radio_calibration_t
{
@ -22,7 +22,10 @@ typedef struct __mavlink_radio_calibration_t
/**
* @brief Send a radio_calibration message
* @brief Pack a radio_calibration 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 aileron Aileron setpoints: high, center, low
* @param elevator Elevator setpoints: high, center, low
@ -37,27 +40,75 @@ static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uin
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION;
i += put_array_by_index((int8_t*)aileron, sizeof(float)*3, i, msg->payload); //Aileron setpoints: high, center, low
i += put_array_by_index((int8_t*)elevator, sizeof(float)*3, i, msg->payload); //Elevator setpoints: high, center, low
i += put_array_by_index((int8_t*)rudder, sizeof(float)*3, i, msg->payload); //Rudder setpoints: high, center, low
i += put_array_by_index((int8_t*)gyro, sizeof(float)*2, i, msg->payload); //Tail gyro mode/gain setpoints: heading hold, rate mode
i += put_array_by_index((int8_t*)pitch, sizeof(float)*5, i, msg->payload); //Pitch curve setpoints (every 25%)
i += put_array_by_index((int8_t*)throttle, sizeof(float)*5, i, msg->payload); //Throttle curve setpoints (every 25%)
i += put_array_by_index((const int8_t*)aileron, sizeof(float)*3, i, msg->payload); // Aileron setpoints: high, center, low
i += put_array_by_index((const int8_t*)elevator, sizeof(float)*3, i, msg->payload); // Elevator setpoints: high, center, low
i += put_array_by_index((const int8_t*)rudder, sizeof(float)*3, i, msg->payload); // Rudder setpoints: high, center, low
i += put_array_by_index((const int8_t*)gyro, sizeof(float)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode
i += put_array_by_index((const int8_t*)pitch, sizeof(float)*5, i, msg->payload); // Pitch curve setpoints (every 25%)
i += put_array_by_index((const int8_t*)throttle, sizeof(float)*5, i, msg->payload); // Throttle curve setpoints (every 25%)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a radio_calibration 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 aileron Aileron setpoints: high, center, low
* @param elevator Elevator setpoints: high, center, low
* @param rudder Rudder setpoints: high, center, low
* @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode
* @param pitch Pitch curve setpoints (every 25%)
* @param throttle Throttle curve setpoints (every 25%)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION;
i += put_array_by_index((const int8_t*)aileron, sizeof(float)*3, i, msg->payload); // Aileron setpoints: high, center, low
i += put_array_by_index((const int8_t*)elevator, sizeof(float)*3, i, msg->payload); // Elevator setpoints: high, center, low
i += put_array_by_index((const int8_t*)rudder, sizeof(float)*3, i, msg->payload); // Rudder setpoints: high, center, low
i += put_array_by_index((const int8_t*)gyro, sizeof(float)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode
i += put_array_by_index((const int8_t*)pitch, sizeof(float)*5, i, msg->payload); // Pitch curve setpoints (every 25%)
i += put_array_by_index((const int8_t*)throttle, sizeof(float)*5, i, msg->payload); // Throttle curve setpoints (every 25%)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a radio_calibration 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 radio_calibration C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration)
{
return mavlink_msg_radio_calibration_pack(system_id, component_id, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle);
}
/**
* @brief Send a radio_calibration message
* @param chan MAVLink channel to send the message
*
* @param aileron Aileron setpoints: high, center, low
* @param elevator Elevator setpoints: high, center, low
* @param rudder Rudder setpoints: high, center, low
* @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode
* @param pitch Pitch curve setpoints (every 25%)
* @param throttle Throttle curve setpoints (every 25%)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle)
{
mavlink_message_t msg;
mavlink_msg_radio_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, aileron, elevator, rudder, gyro, pitch, throttle);
mavlink_msg_radio_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, aileron, elevator, rudder, gyro, pitch, throttle);
mavlink_send_uart(chan, &msg);
}
@ -136,6 +187,12 @@ static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_
return sizeof(float)*5;
}
/**
* @brief Decode a radio_calibration message into a struct
*
* @param msg The message to decode
* @param radio_calibration C-struct to decode the message contents into
*/
static inline void mavlink_msg_radio_calibration_decode(const mavlink_message_t* msg, mavlink_radio_calibration_t* radio_calibration)
{
mavlink_msg_radio_calibration_get_aileron(msg, radio_calibration->aileron);

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_request_rc_channels_t
/**
* @brief Send a request_rc_channels message
* @brief Pack a request_rc_channels 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 enabled True: start sending data; False: stop sending data
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,22 +24,55 @@ static inline uint16_t mavlink_msg_request_rc_channels_pack(uint8_t system_id, u
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS;
i += put_uint8_t_by_index(enabled, i, msg->payload); //True: start sending data; False: stop sending data
i += put_uint8_t_by_index(enabled, i, msg->payload); // True: start sending data; False: stop sending data
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a request_rc_channels 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 enabled True: start sending data; False: stop sending data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS;
i += put_uint8_t_by_index(enabled, i, msg->payload); // True: start sending data; False: stop sending data
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a request_rc_channels 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 request_rc_channels C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_rc_channels_t* request_rc_channels)
{
return mavlink_msg_request_rc_channels_pack(system_id, component_id, msg, request_rc_channels->enabled);
}
/**
* @brief Send a request_rc_channels message
* @param chan MAVLink channel to send the message
*
* @param enabled True: start sending data; False: stop sending data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_rc_channels_send(mavlink_channel_t chan, uint8_t enabled)
{
mavlink_message_t msg;
mavlink_msg_request_rc_channels_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enabled);
mavlink_msg_request_rc_channels_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled);
mavlink_send_uart(chan, &msg);
}
@ -53,6 +89,12 @@ static inline uint8_t mavlink_msg_request_rc_channels_get_enabled(const mavlink_
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Decode a request_rc_channels message into a struct
*
* @param msg The message to decode
* @param request_rc_channels C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_rc_channels_decode(const mavlink_message_t* msg, mavlink_request_rc_channels_t* request_rc_channels)
{
request_rc_channels->enabled = mavlink_msg_request_rc_channels_get_enabled(msg);

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Monday, October 25 2010, 17:38 UTC
* Generated on Tuesday, February 15 2011, 15:58 UTC
*/
#ifndef UALBERTA_H
#define UALBERTA_H
@ -17,10 +17,25 @@ extern "C" {
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS
// MESSAGE DEFINITIONS
#include "./mavlink_msg_nav_filter_bias.h"
#include "./mavlink_msg_request_rc_channels.h"
#include "./mavlink_msg_radio_calibration.h"
#include "./mavlink_msg_request_radio_calibration.h"
#ifdef __cplusplus
}
#endif

View File

@ -79,16 +79,6 @@
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_R_WAYPOINT" value="23">
<description>Navigate to waypoint, relative to home.</description>
<param index="1">Hold time (ignored by fixed wing, time to stay at waypoint for rotary wing)</param>
<param index="2">Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)</param>
<param index="3">0 to pass through the WP, if > 0 radius to pass by WP. Allows trajectory control.</param>
<param index="4">Desired yaw angle</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_LAST" value="95">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<param index="1">Empty</param>
@ -241,9 +231,9 @@
<entry name="MAV_DATA_STREAM_RC_CHANNELS" value="3"><description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description></entry>
<entry name="MAV_DATA_STREAM_RAW_CONTROLLER" value="4"><description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description></entry>
<entry name="MAV_DATA_STREAM_POSITION" value="6"><description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA1" value="250"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA2" value="251"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA3" value="252"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA1" value="10"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA2" value="11"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA3" value="12"><description>Dependent on the autopilot</description></entry>
</enum>
</enums>
@ -273,13 +263,28 @@
<field name="time" type="uint64_t">Unix timestamp in microseconds</field>
</message>
<message name="SYSTEM_TIME_UTC" id="4">
<message name="SYSTEM_TIME_UTC" id="4">
<description>UTC date and time from GPS module</description>
<field name="utc_date" type="uint32_t">GPS UTC date ddmmyy</field>
<field name="utc_time" type="uint32_t">GPS UTC time hhmmss</field>
</message>
<message name="ACTION_ACK" id="9">
<message name="CHANGE_OPERATOR_CONTROL" id="5">
<description>Request to control this MAV</description>
<field name="target_system" type="uint8_t">System the GCS requests control for</field>
<field name="control_request" type="uint8_t">0: request control of this MAV, 1: Release control of this MAV</field>
<field name="version" type="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.</field>
<field name="passkey" type="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 "!?,.-"</field>
</message>
<message name="CHANGE_OPERATOR_CONTROL_ACK" id="6">
<description>Accept / deny control of this MAV</description>
<field name="gcs_system_id" type="uint8_t">ID of the GCS this message </field>
<field name="control_request" type="uint8_t">0: request control of this MAV, 1: Release control of this MAV</field>
<field name="ack" type="uint8_t">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field>
</message>
<message name="ACTION_ACK" id="9">
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field name="action" type="uint8_t">The action id</field>
<field name="result" type="uint8_t">0: Action DENIED, 1: Action executed</field>
@ -309,7 +314,7 @@
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="param_id" type="array[15]">Onboard parameter id</field>
<field name="param_index" type="uint16_t">Parameter index</field>
<field name="param_index" type="int16_t">Parameter index. Send -1 to use the param ID field as identifier</field>
</message>
<message name="PARAM_REQUEST_LIST" id="21">
@ -338,7 +343,7 @@
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<field name="lat" type="int32_t">Latitude in 1E7 degrees</field>
<field name="lon" type="int32_t">Longitude in 1E7 degrees</field>
<field name="alt" type="int32_t">Altitude in 1E3 meters (millimeters)</field>
@ -432,7 +437,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<field name="lat" type="float">Latitude in degrees</field>
<field name="lon" type="float">Longitude in degrees</field>
<field name="alt" type="float">Altitude in meters</field>