mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Rover: config.h correct whitespace, remove tabs
This commit is contained in:
parent
283a199268
commit
597423fffc
@ -39,32 +39,32 @@
|
|||||||
// HIL_MODE OPTIONAL
|
// HIL_MODE OPTIONAL
|
||||||
|
|
||||||
#ifndef HIL_MODE
|
#ifndef HIL_MODE
|
||||||
#define HIL_MODE HIL_MODE_DISABLED
|
#define HIL_MODE HIL_MODE_DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
# define BATTERY_PIN_1 1
|
#define BATTERY_PIN_1 1
|
||||||
# define CURRENT_PIN_1 2
|
#define CURRENT_PIN_1 2
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
# define BATTERY_PIN_1 -1
|
#define BATTERY_PIN_1 -1
|
||||||
# define CURRENT_PIN_1 -1
|
#define CURRENT_PIN_1 -1
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
# define BATTERY_PIN_1 -1
|
#define BATTERY_PIN_1 -1
|
||||||
# define CURRENT_PIN_1 -1
|
#define CURRENT_PIN_1 -1
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
# define BATTERY_PIN_1 -1
|
#define BATTERY_PIN_1 -1
|
||||||
# define CURRENT_PIN_1 -1
|
#define CURRENT_PIN_1 -1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// HIL_MODE OPTIONAL
|
// HIL_MODE OPTIONAL
|
||||||
|
|
||||||
#ifndef HIL_MODE
|
#ifndef HIL_MODE
|
||||||
#define HIL_MODE HIL_MODE_DISABLED
|
#define HIL_MODE HIL_MODE_DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef MAV_SYSTEM_ID
|
#ifndef MAV_SYSTEM_ID
|
||||||
# define MAV_SYSTEM_ID 1
|
#define MAV_SYSTEM_ID 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
@ -73,29 +73,29 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#ifndef FRSKY_TELEM_ENABLED
|
#ifndef FRSKY_TELEM_ENABLED
|
||||||
#define FRSKY_TELEM_ENABLED ENABLED
|
#define FRSKY_TELEM_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifndef CH7_OPTION
|
#ifndef CH7_OPTION
|
||||||
# define CH7_OPTION CH7_SAVE_WP
|
#define CH7_OPTION CH7_SAVE_WP
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef TUNING_OPTION
|
#ifndef TUNING_OPTION
|
||||||
# define TUNING_OPTION TUN_NONE
|
#define TUNING_OPTION TUN_NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// INPUT_VOLTAGE
|
// INPUT_VOLTAGE
|
||||||
//
|
//
|
||||||
#ifndef INPUT_VOLTAGE
|
#ifndef INPUT_VOLTAGE
|
||||||
# define INPUT_VOLTAGE 4.68 // 4.68 is the average value for a sample set. This is the value at the processor with 5.02 applied at the servo rail
|
#define INPUT_VOLTAGE 4.68 // 4.68 is the average value for a sample set. This is the value at the processor with 5.02 applied at the servo rail
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// MAGNETOMETER
|
// MAGNETOMETER
|
||||||
#ifndef MAGNETOMETER
|
#ifndef MAGNETOMETER
|
||||||
# define MAGNETOMETER ENABLED
|
#define MAGNETOMETER ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
@ -103,47 +103,47 @@
|
|||||||
// MODE_CHANNEL
|
// MODE_CHANNEL
|
||||||
//
|
//
|
||||||
#ifndef MODE_CHANNEL
|
#ifndef MODE_CHANNEL
|
||||||
# define MODE_CHANNEL 8
|
#define MODE_CHANNEL 8
|
||||||
#endif
|
#endif
|
||||||
#if (MODE_CHANNEL != 5) && (MODE_CHANNEL != 6) && (MODE_CHANNEL != 7) && (MODE_CHANNEL != 8)
|
#if (MODE_CHANNEL != 5) && (MODE_CHANNEL != 6) && (MODE_CHANNEL != 7) && (MODE_CHANNEL != 8)
|
||||||
# error XXX
|
#error XXX
|
||||||
# error XXX You must set MODE_CHANNEL to 5, 6, 7 or 8
|
#error XXX You must set MODE_CHANNEL to 5, 6, 7 or 8
|
||||||
# error XXX
|
#error XXX
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(MODE_1)
|
#if !defined(MODE_1)
|
||||||
# define MODE_1 LEARNING
|
#define MODE_1 LEARNING
|
||||||
#endif
|
#endif
|
||||||
#if !defined(MODE_2)
|
#if !defined(MODE_2)
|
||||||
# define MODE_2 LEARNING
|
#define MODE_2 LEARNING
|
||||||
#endif
|
#endif
|
||||||
#if !defined(MODE_3)
|
#if !defined(MODE_3)
|
||||||
# define MODE_3 LEARNING
|
#define MODE_3 LEARNING
|
||||||
#endif
|
#endif
|
||||||
#if !defined(MODE_4)
|
#if !defined(MODE_4)
|
||||||
# define MODE_4 LEARNING
|
#define MODE_4 LEARNING
|
||||||
#endif
|
#endif
|
||||||
#if !defined(MODE_5)
|
#if !defined(MODE_5)
|
||||||
# define MODE_5 LEARNING
|
#define MODE_5 LEARNING
|
||||||
#endif
|
#endif
|
||||||
#if !defined(MODE_6)
|
#if !defined(MODE_6)
|
||||||
# define MODE_6 MANUAL
|
#define MODE_6 MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// failsafe defaults
|
// failsafe defaults
|
||||||
#ifndef THROTTLE_FAILSAFE
|
#ifndef THROTTLE_FAILSAFE
|
||||||
# define THROTTLE_FAILSAFE ENABLED
|
#define THROTTLE_FAILSAFE ENABLED
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_FS_VALUE
|
#ifndef THROTTLE_FS_VALUE
|
||||||
# define THROTTLE_FS_VALUE 950
|
#define THROTTLE_FS_VALUE 950
|
||||||
#endif
|
#endif
|
||||||
#ifndef LONG_FAILSAFE_ACTION
|
#ifndef LONG_FAILSAFE_ACTION
|
||||||
# define LONG_FAILSAFE_ACTION 0
|
#define LONG_FAILSAFE_ACTION 0
|
||||||
#endif
|
#endif
|
||||||
#ifndef GCS_HEARTBEAT_FAILSAFE
|
#ifndef GCS_HEARTBEAT_FAILSAFE
|
||||||
# define GCS_HEARTBEAT_FAILSAFE DISABLED
|
#define GCS_HEARTBEAT_FAILSAFE DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
@ -151,7 +151,7 @@
|
|||||||
// THROTTLE_OUT
|
// THROTTLE_OUT
|
||||||
//
|
//
|
||||||
#ifndef THROTTE_OUT
|
#ifndef THROTTE_OUT
|
||||||
# define THROTTLE_OUT ENABLED
|
#define THROTTLE_OUT ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
@ -165,73 +165,73 @@
|
|||||||
// GROUND_START_DELAY
|
// GROUND_START_DELAY
|
||||||
//
|
//
|
||||||
#ifndef GROUND_START_DELAY
|
#ifndef GROUND_START_DELAY
|
||||||
# define GROUND_START_DELAY 0
|
#define GROUND_START_DELAY 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// MOUNT (ANTENNA OR CAMERA)
|
// MOUNT (ANTENNA OR CAMERA)
|
||||||
//
|
//
|
||||||
#ifndef MOUNT
|
#ifndef MOUNT
|
||||||
# define MOUNT ENABLED
|
#define MOUNT ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// CAMERA control
|
// CAMERA control
|
||||||
//
|
//
|
||||||
#ifndef CAMERA
|
#ifndef CAMERA
|
||||||
# define CAMERA ENABLED
|
#define CAMERA ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// AIRSPEED_CRUISE
|
// AIRSPEED_CRUISE
|
||||||
//
|
//
|
||||||
#ifndef SPEED_CRUISE
|
#ifndef SPEED_CRUISE
|
||||||
# define SPEED_CRUISE 5 // in m/s
|
#define SPEED_CRUISE 5 // in m/s
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef TURN_GAIN
|
#ifndef TURN_GAIN
|
||||||
# define TURN_GAIN 5
|
#define TURN_GAIN 5
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Servo Mapping
|
// Servo Mapping
|
||||||
//
|
//
|
||||||
#ifndef THROTTLE_MIN
|
#ifndef THROTTLE_MIN
|
||||||
# define THROTTLE_MIN 0 // percent
|
#define THROTTLE_MIN 0 // percent
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_CRUISE
|
#ifndef THROTTLE_CRUISE
|
||||||
# define THROTTLE_CRUISE 45
|
#define THROTTLE_CRUISE 45
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_MAX
|
#ifndef THROTTLE_MAX
|
||||||
# define THROTTLE_MAX 100
|
#define THROTTLE_MAX 100
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Attitude control gains
|
// Attitude control gains
|
||||||
//
|
//
|
||||||
#ifndef SERVO_STEER_P
|
#ifndef SERVO_STEER_P
|
||||||
# define SERVO_STEER_P 0.4
|
#define SERVO_STEER_P 0.4
|
||||||
#endif
|
#endif
|
||||||
#ifndef SERVO_STEER_I
|
#ifndef SERVO_STEER_I
|
||||||
# define SERVO_STEER_I 0.0
|
#define SERVO_STEER_I 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef SERVO_STEER_D
|
#ifndef SERVO_STEER_D
|
||||||
# define SERVO_STEER_D 0.0
|
#define SERVO_STEER_D 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef SERVO_STEER_INT_MAX
|
#ifndef SERVO_STEER_INT_MAX
|
||||||
# define SERVO_STEER_INT_MAX 5
|
#define SERVO_STEER_INT_MAX 5
|
||||||
#endif
|
#endif
|
||||||
#define SERVO_STEER_INT_MAX_CENTIDEGREE SERVO_STEER_INT_MAX*100
|
#define SERVO_STEER_INT_MAX_CENTIDEGREE (SERVO_STEER_INT_MAX * 100)
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Dataflash logging control
|
// Dataflash logging control
|
||||||
//
|
//
|
||||||
#ifndef LOGGING_ENABLED
|
#ifndef LOGGING_ENABLED
|
||||||
# define LOGGING_ENABLED ENABLED
|
#define LOGGING_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define DEFAULT_LOG_BITMASK 0xffff
|
#define DEFAULT_LOG_BITMASK 0xffff
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
@ -240,12 +240,12 @@
|
|||||||
|
|
||||||
// use this to enable servos in HIL mode
|
// use this to enable servos in HIL mode
|
||||||
#ifndef HIL_SERVOS
|
#ifndef HIL_SERVOS
|
||||||
# define HIL_SERVOS DISABLED
|
#define HIL_SERVOS DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// use this to completely disable the CLI
|
// use this to completely disable the CLI
|
||||||
#ifndef CLI_ENABLED
|
#ifndef CLI_ENABLED
|
||||||
#define CLI_ENABLED ENABLED
|
#define CLI_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
|
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
|
||||||
@ -253,5 +253,5 @@
|
|||||||
// position (to for example return to switched mode after failsafe or
|
// position (to for example return to switched mode after failsafe or
|
||||||
// fence breach)
|
// fence breach)
|
||||||
#ifndef RESET_SWITCH_CHAN_PWM
|
#ifndef RESET_SWITCH_CHAN_PWM
|
||||||
# define RESET_SWITCH_CHAN_PWM 1750
|
#define RESET_SWITCH_CHAN_PWM 1750
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user