Updated mavlink.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1066 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-07 21:25:25 +00:00
parent efa785394a
commit 887c0b8d4a
7 changed files with 30 additions and 18 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, December 7 2010, 13:34 UTC
*/
#ifndef COMMON_H
#define COMMON_H
@ -63,6 +63,8 @@ extern "C" {
#include "./mavlink_msg_request_dynamic_gyro_calibration.h"
#include "./mavlink_msg_request_static_calibration.h"
#include "./mavlink_msg_manual_control.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_gps_local_origin_set.h"
#include "./mavlink_msg_statustext.h"
#include "./mavlink_msg_debug.h"
#ifdef __cplusplus

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, December 7 2010, 13:34 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -39,6 +39,7 @@ enum MAV_ACTION {
MAV_ACTION_NAVIGATE = 25,
MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACTION_NB ///< Number of MAV actions
};

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:43 UTC
* Generated on Tuesday, December 7 2010, 13:34 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 Thursday, December 2 2010, 10:43 UTC
* Generated on Tuesday, December 7 2010, 13:34 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H
@ -31,7 +31,6 @@ enum SLUGS_PID_INDX_IDS
// MESSAGE DEFINITIONS
#include "./mavlink_msg_attitude_control.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_set_cam_shutter.h"
#include "./mavlink_msg_image_triggered.h"
#include "./mavlink_msg_image_trigger_control.h"

View File

@ -1,5 +1,6 @@
<?xml version="1.0"?>
<mavlink>
<messages>
<message name="HEARTBEAT" id="0">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
@ -391,6 +392,23 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
</message>
<message name="DEBUG_VECT" id="70">
<field name="name" type="array[10]">Name</field>
<field name="usec" type="uint64_t">Timestamp</field>
<field name="x" type="float">x</field>
<field name="y" type="float">y</field>
<field name="z" type="float">z</field>
</message>
<message name="GPS_LOCAL_ORIGIN_SET" id="71">
<description>Once the MAV sets a new GPS-Local correspondence, this message announces </description>
<field name="latitude" type="float">Latitude (WGS84)</field>
<field name="longitude" type="float">Longitude (WGS84)</field>
<field name="altitude" type="float">Altitude(WGS84)</field>
<field name="x" type="float">Local X coordinate in meters</field>
<field name="y" type="float">Local Y coordinate in meters</field>
<field name="z" type="float">Local Z coordinate in meters</field>
</message>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->

View File

@ -24,14 +24,6 @@
<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
</message>
<message name="DEBUG_VECT" id="90">
<field name="name" type="array[10]">Name</field>
<field name="usec" type="uint64_t">Timestamp</field>
<field name="x" type="float">x</field>
<field name="y" type="float">y</field>
<field name="z" type="float">z</field>
</message>
<message name="SET_CAM_SHUTTER" id="100">
<field name="cam_no" type="uint8_t">Camera id</field>
<field name="cam_mode" type="uint8_t">Camera mode: 0 = auto, 1 = manual</field>