GCS_MAVLink: generate after adding RC reciever to SYS_STATUS enum

This commit is contained in:
Randy Mackay 2013-10-21 22:20:57 +09:00
parent d1906abb5c
commit 0049351f2f
4 changed files with 5 additions and 8 deletions

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Oct 11 21:12:15 2013"
#define MAVLINK_BUILD_DATE "Mon Oct 21 22:18:41 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

View File

@ -222,7 +222,8 @@ enum MAV_SYS_STATUS_SENSOR
MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */
MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */
MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */
MAV_SYS_STATUS_SENSOR_ENUM_END=32769, /* | */
MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */
MAV_SYS_STATUS_SENSOR_ENUM_END=65537, /* | */
};
#endif

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Oct 11 21:12:15 2013"
#define MAVLINK_BUILD_DATE "Mon Oct 21 22:18:41 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

View File

@ -9,10 +9,6 @@
#endif
#include <math.h>
#ifndef M_PI_2
#define M_PI_2 ((float)asin(1))
#endif
/**
* @file mavlink_conversions.h
*
@ -132,4 +128,4 @@ MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, flo
dcm[2][2] = cosPhi * cosThe;
}
#endif
#endif