mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
uncrustify ArduPlane/defines.h
This commit is contained in:
parent
2c56e5c690
commit
b960619195
@ -13,7 +13,8 @@
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
|
||||
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an
|
||||
// arbitrary representation of servo max travel.
|
||||
|
||||
// failsafe
|
||||
// ----------------------
|
||||
@ -61,30 +62,45 @@
|
||||
// Auto Pilot modes
|
||||
// ----------------
|
||||
#define MANUAL 0
|
||||
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
|
||||
#define CIRCLE 1 // When flying sans GPS, and we loose
|
||||
// the radio, just circle
|
||||
#define STABILIZE 2
|
||||
|
||||
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle
|
||||
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed
|
||||
#define FLY_BY_WIRE_C 7 // Fly By Wire C has left stick horizontal => desired roll angle, left stick vertical => desired climb rate, right stick vertical => desired airspeed
|
||||
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal =>
|
||||
// desired roll angle, left stick vertical =>
|
||||
// desired pitch angle, right stick vertical =
|
||||
// manual throttle
|
||||
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal =>
|
||||
// desired roll angle, left stick vertical =>
|
||||
// desired pitch angle, right stick vertical
|
||||
// => desired airspeed
|
||||
#define FLY_BY_WIRE_C 7 // Fly By Wire C has left stick horizontal =>
|
||||
// desired roll angle, left stick vertical =>
|
||||
// desired climb rate, right stick vertical =>
|
||||
// desired airspeed
|
||||
// Fly By Wire B and Fly By Wire C require airspeed sensor
|
||||
#define AUTO 10
|
||||
#define RTL 11
|
||||
#define LOITER 12
|
||||
//#define TAKEOFF 13 // This is not used by APM. It appears here for consistency with ACM
|
||||
//#define LAND 14 // This is not used by APM. It appears here for consistency with ACM
|
||||
//#define TAKEOFF 13 // This is not used by APM. It appears here
|
||||
// for consistency with ACM
|
||||
//#define LAND 14 // This is not used by APM. It appears here for
|
||||
// consistency with ACM
|
||||
#define GUIDED 15
|
||||
#define INITIALISING 16 // in startup routines
|
||||
|
||||
|
||||
// Commands - Note that APM now uses a subset of the MAVLink protocol commands. See enum MAV_CMD in the GCS_Mavlink library
|
||||
#define CMD_BLANK 0 // there is no command stored in the mem location requested
|
||||
// Commands - Note that APM now uses a subset of the MAVLink protocol
|
||||
// commands. See enum MAV_CMD in the GCS_Mavlink library
|
||||
#define CMD_BLANK 0 // there is no command stored in the mem location
|
||||
// requested
|
||||
#define NO_COMMAND 0
|
||||
#define WAIT_COMMAND 255
|
||||
|
||||
// Command/Waypoint/Location Options Bitmask
|
||||
//--------------------
|
||||
#define MASK_OPTIONS_RELATIVE_ALT (1<<0) // 1 = Relative altitude
|
||||
#define MASK_OPTIONS_RELATIVE_ALT (1<<0) // 1 = Relative
|
||||
// altitude
|
||||
|
||||
//repeating events
|
||||
#define NO_REPEAT 0
|
||||
@ -181,7 +197,8 @@ enum gcs_severity {
|
||||
#define EVENT_LOOP 4
|
||||
|
||||
// Climb rate calculations
|
||||
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
|
||||
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to
|
||||
// regress a climb rate from
|
||||
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1024.0))*g.volt_div_ratio
|
||||
@ -197,13 +214,16 @@ enum gcs_severity {
|
||||
#define AN4 4
|
||||
#define AN5 5
|
||||
|
||||
#define SPEEDFILT 400 // centimeters/second; the speed below which a groundstart will be triggered
|
||||
#define SPEEDFILT 400 // centimeters/second; the speed below
|
||||
// which a groundstart will be
|
||||
// triggered
|
||||
|
||||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// parameters get the first 1280 bytes of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP
|
||||
#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other
|
||||
// WP
|
||||
#define WP_SIZE 15
|
||||
|
||||
// fence points are stored at the end of the EEPROM
|
||||
@ -211,11 +231,16 @@ enum gcs_severity {
|
||||
#define FENCE_WP_SIZE sizeof(Vector2l)
|
||||
#define FENCE_START_BYTE (EEPROM_MAX_ADDR-(MAX_FENCEPOINTS*FENCE_WP_SIZE))
|
||||
|
||||
#define MAX_WAYPOINTS ((FENCE_START_BYTE - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe
|
||||
#define MAX_WAYPOINTS ((FENCE_START_BYTE - WP_START_BYTE) / WP_SIZE) - 1 // -
|
||||
// 1
|
||||
// to
|
||||
// be
|
||||
// safe
|
||||
|
||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||
|
||||
// convert a boolean (0 or 1) to a sign for multiplying (0 maps to 1, 1 maps to -1)
|
||||
// convert a boolean (0 or 1) to a sign for multiplying (0 maps to 1, 1 maps
|
||||
// to -1)
|
||||
#define BOOL_TO_SIGN(bvalue) ((bvalue) ? -1 : 1)
|
||||
|
||||
// mark a function as not to be inlined
|
||||
|
Loading…
Reference in New Issue
Block a user