From a54cd57568f1350cf4ca09e2f0e2095df52afad8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Apr 2012 10:44:24 +1000 Subject: [PATCH] MAVLink: imported new mavlink header updates this fixes the camera control code which was broken by a previous import --- .../mavlink/v0.9/ardupilotmega/version.h | 2 +- .../include/mavlink/v0.9/checksum.h | 2 +- .../include/mavlink/v0.9/common/common.h | 49 ------------------- .../include/mavlink/v0.9/common/version.h | 2 +- .../include/mavlink/v0.9/mavlink_helpers.h | 33 ++++++++++--- .../include/mavlink/v0.9/mavlink_types.h | 35 ++++++++++--- .../include/mavlink/v0.9/protocol.h | 13 +++-- .../mavlink/v1.0/ardupilotmega/version.h | 2 +- .../include/mavlink/v1.0/common/common.h | 42 ---------------- .../include/mavlink/v1.0/common/version.h | 2 +- 10 files changed, 68 insertions(+), 114 deletions(-) diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h index cbf2f9b1ed..319b4dbed0 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:46 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h index b70991f5ab..4f4cce02fc 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h @@ -52,7 +52,7 @@ static inline void crc_init(uint16_t* crcAccum) * @param length length of the byte array * @return the checksum over the buffer bytes **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) { uint16_t crcTmp; crc_init(&crcTmp); diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h index 84538ed570..210baad49b 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h @@ -43,55 +43,6 @@ extern "C" { // ENUM DEFINITIONS -/** @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. This command list is similar what - ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Turns| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X seconds |Seconds (decimal)| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - 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)| Empty| Empty| Empty| Empty| */ - 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)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - 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 number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - devices such as cameras. - |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_ENUM_END=246, /* | */ -}; -#endif - /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h index 5ca3dc8ca3..872c25a677 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:54 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h index 98250e1ac8..804490add2 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h @@ -18,6 +18,24 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) return &m_mavlink_status[chan]; } +/* + internal function to give access to the channel buffer for each channel + */ +MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) +{ + +#if MAVLINK_EXTERNAL_RX_BUFFER + // No m_mavlink_message array defined in function, + // has to be defined externally +#ifndef m_mavlink_message +#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];) +#endif +#else + static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_buffer[chan]; +} + /** * @brief Finalize a MAVLink message with channel assignment * @@ -120,7 +138,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint */ MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) { - memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; } @@ -182,8 +200,6 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) */ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) { - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; - /* default message crc function. You can override this per-system to put this data in a different memory segment @@ -195,7 +211,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa #endif #endif - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message + mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status int bufferIndex = 0; @@ -209,14 +225,15 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa { status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; rxmsg->len = 0; + rxmsg->magic = c; mavlink_start_checksum(rxmsg); } break; case MAVLINK_PARSE_STATE_GOT_STX: if (status->msg_received - /* Support shorter buffers than the - default maximum packet size */ +/* Support shorter buffers than the + default maximum packet size */ #if (MAVLINK_MAX_PAYLOAD_LEN < 255) || c > MAVLINK_MAX_PAYLOAD_LEN #endif @@ -269,7 +286,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa break; case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; mavlink_update_checksum(rxmsg, c); if (status->packet_idx == rxmsg->len) { @@ -296,6 +313,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa else { status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; } break; @@ -317,6 +335,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa // Successfully got message status->msg_received = 1; status->parse_state = MAVLINK_PARSE_STATE_IDLE; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); } break; diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h index 630cb84b77..9d04155c77 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h @@ -180,11 +180,26 @@ enum MAVLINK_DATA_STREAM_TYPE #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 +#define MAVLINK_EXTENDED_HEADER_LEN 14 + +#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) + /* full fledged 32bit++ OS */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 +#else + /* small microcontrollers */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 +#endif + +#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) + typedef struct param_union { union { float param_float; int32_t param_int32; uint32_t param_uint32; + uint8_t param_uint8; + uint8_t bytes[4]; }; uint8_t type; } mavlink_param_union_t; @@ -209,6 +224,14 @@ typedef struct __mavlink_message { uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; } mavlink_message_t; + +typedef struct __mavlink_extended_message { + mavlink_message_t base_msg; + int32_t extended_payload_len; ///< Length of extended payload if any + uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; +} mavlink_extended_message_t; + + typedef enum { MAVLINK_TYPE_CHAR = 0, MAVLINK_TYPE_UINT8_T = 1, @@ -229,9 +252,9 @@ typedef struct __mavlink_field_info { const char *name; // name of this field const char *print_format; // printing format hint, or NULL mavlink_message_type_t type; // type of this field - unsigned array_length; // if non-zero, field is an array - unsigned wire_offset; // offset of each field in the payload - unsigned structure_offset; // offset in a C structure + unsigned int array_length; // if non-zero, field is an array + unsigned int wire_offset; // offset of each field in the payload + unsigned int structure_offset; // offset in a C structure } mavlink_field_info_t; // note that in this structure the order of fields is the order @@ -242,12 +265,12 @@ typedef struct __mavlink_message_info { mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information } mavlink_message_info_t; -#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) +#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) // checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg)) -#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) +#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) +#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) typedef enum { MAVLINK_COMM_0, diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h index 05195c3691..7b3e3c0bd2 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h @@ -155,7 +155,7 @@ static inline void byte_copy_8(char *dst, const char *src) /* like memcpy(), but if src is NULL, do a memset to zero - */ +*/ static void mav_array_memcpy(void *dest, const void *src, size_t n) { if (src == NULL) { @@ -171,6 +171,7 @@ static void mav_array_memcpy(void *dest, const void *src, size_t n) static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) { mav_array_memcpy(&buf[wire_offset], b, array_length); + } /* @@ -179,6 +180,7 @@ static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const cha static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) { mav_array_memcpy(&buf[wire_offset], b, array_length); + } /* @@ -187,6 +189,7 @@ static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) { mav_array_memcpy(&buf[wire_offset], b, array_length); + } #if MAVLINK_NEED_BYTE_SWAP @@ -206,7 +209,7 @@ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, co #define _MAV_PUT_ARRAY(TYPE, V) \ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ { \ - mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \ + mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \ } #endif @@ -219,9 +222,9 @@ _MAV_PUT_ARRAY(int64_t, i64) _MAV_PUT_ARRAY(float, f) _MAV_PUT_ARRAY(double, d) -#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset] #if MAVLINK_NEED_BYTE_SWAP #define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h index 7cc3ee13d9..2f6014644e 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:47 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h index 9a76edeaad..d9851110d3 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h @@ -239,48 +239,6 @@ enum MAVLINK_DATA_STREAM_TYPE }; #endif -/** @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. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - 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)| Empty| Empty| Empty| Empty| */ - 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)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - 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 number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_ENUM_END=401, /* | */ -}; -#endif - /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */ diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h index 0e49f8232e..3cd0335edd 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:54 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101