diff --git a/libraries/GCS_MAVLink/include/common/common.h b/libraries/GCS_MAVLink/include/common/common.h index db8710e1d0..41cba5f284 100644 --- a/libraries/GCS_MAVLink/include/common/common.h +++ b/libraries/GCS_MAVLink/include/common/common.h @@ -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 diff --git a/libraries/GCS_MAVLink/include/common/mavlink.h b/libraries/GCS_MAVLink/include/common/mavlink.h index 4827e0b674..a5c849425e 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink.h +++ b/libraries/GCS_MAVLink/include/common/mavlink.h @@ -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 diff --git a/libraries/GCS_MAVLink/include/mavlink_types.h b/libraries/GCS_MAVLink/include/mavlink_types.h index 7fc8458572..64fe89e892 100644 --- a/libraries/GCS_MAVLink/include/mavlink_types.h +++ b/libraries/GCS_MAVLink/include/mavlink_types.h @@ -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 }; @@ -48,11 +49,11 @@ enum MAV_MODE 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_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_TEST1 = 5, ///< 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_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive + 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_TEST2 = 6, ///< 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_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back }; diff --git a/libraries/GCS_MAVLink/include/pixhawk/mavlink.h b/libraries/GCS_MAVLink/include/pixhawk/mavlink.h index f7cf5377db..e2dbe043de 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/mavlink.h +++ b/libraries/GCS_MAVLink/include/pixhawk/mavlink.h @@ -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 diff --git a/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h b/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h index d3436195e9..b7a7616cb3 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h +++ b/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h @@ -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" diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index debd9a08a2..f5f8128c34 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -1,5 +1,6 @@ + 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). @@ -391,6 +392,23 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se thrust auto:0, manual:1 + + Name + Timestamp + x + y + z + + + + Once the MAV sets a new GPS-Local correspondence, this message announces + Latitude (WGS84) + Longitude (WGS84) + Altitude(WGS84) + Local X coordinate in meters + Local Y coordinate in meters + Local Z coordinate in meters + diff --git a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml index 758585c32a..2fb61cac33 100644 --- a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml +++ b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml @@ -24,14 +24,6 @@ thrust auto:0, manual:1 - - Name - Timestamp - x - y - z - - Camera id Camera mode: 0 = auto, 1 = manual