Browse Source

Updated mavlink.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1066 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
james.goppert 14 years ago
parent
commit
887c0b8d4a
  1. 4
      libraries/GCS_MAVLink/include/common/common.h
  2. 2
      libraries/GCS_MAVLink/include/common/mavlink.h
  3. 11
      libraries/GCS_MAVLink/include/mavlink_types.h
  4. 2
      libraries/GCS_MAVLink/include/pixhawk/mavlink.h
  5. 3
      libraries/GCS_MAVLink/include/pixhawk/pixhawk.h
  6. 18
      libraries/GCS_MAVLink/message_definitions/common.xml
  7. 8
      libraries/GCS_MAVLink/message_definitions/pixhawk.xml

4
libraries/GCS_MAVLink/include/common/common.h

@ -1,7 +1,7 @@
/** @file /** @file
* @brief MAVLink comm protocol. * @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink * @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 #ifndef COMMON_H
#define COMMON_H #define COMMON_H
@ -63,6 +63,8 @@ extern "C" {
#include "./mavlink_msg_request_dynamic_gyro_calibration.h" #include "./mavlink_msg_request_dynamic_gyro_calibration.h"
#include "./mavlink_msg_request_static_calibration.h" #include "./mavlink_msg_request_static_calibration.h"
#include "./mavlink_msg_manual_control.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_statustext.h"
#include "./mavlink_msg_debug.h" #include "./mavlink_msg_debug.h"
#ifdef __cplusplus #ifdef __cplusplus

2
libraries/GCS_MAVLink/include/common/mavlink.h

@ -1,7 +1,7 @@
/** @file /** @file
* @brief MAVLink comm protocol. * @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink * @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 #ifndef MAVLINK_H
#define MAVLINK_H #define MAVLINK_H

11
libraries/GCS_MAVLink/include/mavlink_types.h

@ -39,6 +39,7 @@ enum MAV_ACTION {
MAV_ACTION_NAVIGATE = 25, MAV_ACTION_NAVIGATE = 25,
MAV_ACTION_LAND = 26, MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27, MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACTION_NB ///< Number of MAV actions MAV_ACTION_NB ///< Number of MAV actions
}; };
@ -48,11 +49,11 @@ enum MAV_MODE
MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
}; };

2
libraries/GCS_MAVLink/include/pixhawk/mavlink.h

@ -1,7 +1,7 @@
/** @file /** @file
* @brief MAVLink comm protocol. * @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink * @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 #ifndef MAVLINK_H
#define MAVLINK_H #define MAVLINK_H

3
libraries/GCS_MAVLink/include/pixhawk/pixhawk.h

@ -1,7 +1,7 @@
/** @file /** @file
* @brief MAVLink comm protocol. * @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink * @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 #ifndef PIXHAWK_H
#define PIXHAWK_H #define PIXHAWK_H
@ -31,7 +31,6 @@ enum SLUGS_PID_INDX_IDS
// MESSAGE DEFINITIONS // MESSAGE DEFINITIONS
#include "./mavlink_msg_attitude_control.h" #include "./mavlink_msg_attitude_control.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_set_cam_shutter.h" #include "./mavlink_msg_set_cam_shutter.h"
#include "./mavlink_msg_image_triggered.h" #include "./mavlink_msg_image_triggered.h"
#include "./mavlink_msg_image_trigger_control.h" #include "./mavlink_msg_image_trigger_control.h"

18
libraries/GCS_MAVLink/message_definitions/common.xml

@ -1,5 +1,6 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<mavlink> <mavlink>
<messages> <messages>
<message name="HEARTBEAT" id="0"> <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> <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> <field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
</message> </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 --> <!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->

8
libraries/GCS_MAVLink/message_definitions/pixhawk.xml

@ -24,14 +24,6 @@
<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field> <field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
</message> </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"> <message name="SET_CAM_SHUTTER" id="100">
<field name="cam_no" type="uint8_t">Camera id</field> <field name="cam_no" type="uint8_t">Camera id</field>
<field name="cam_mode" type="uint8_t">Camera mode: 0 = auto, 1 = manual</field> <field name="cam_mode" type="uint8_t">Camera mode: 0 = auto, 1 = manual</field>

Loading…
Cancel
Save