mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: set main loop rate from CPU class
Previously this was determined by the board
This commit is contained in:
parent
72d2712c4e
commit
8ac14023b4
@ -59,7 +59,6 @@
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define MAGNETOMETER ENABLED
|
||||
# define MAIN_LOOP_RATE 100
|
||||
# ifdef APM2_BETA_HARDWARE
|
||||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
# else // APM2 Production Hardware (default)
|
||||
@ -71,14 +70,12 @@
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define MAGNETOMETER ENABLED
|
||||
# define OPTFLOW DISABLED
|
||||
# define MAIN_LOOP_RATE 100
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_PX4
|
||||
# define CONFIG_BARO AP_BARO_PX4
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define MAGNETOMETER ENABLED
|
||||
# define OPTFLOW DISABLED
|
||||
# define MAIN_LOOP_RATE 400
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_FLYMAPLE
|
||||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
@ -87,7 +84,6 @@
|
||||
# define MAGNETOMETER ENABLED
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define OPTFLOW DISABLED
|
||||
# define MAIN_LOOP_RATE 400
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_L3G4200D
|
||||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
@ -96,20 +92,20 @@
|
||||
# define MAGNETOMETER ENABLED
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define OPTFLOW DISABLED
|
||||
# define MAIN_LOOP_RATE 400
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_VRBRAIN
|
||||
# define CONFIG_BARO AP_BARO_VRBRAIN
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define MAGNETOMETER ENABLED
|
||||
# define OPTFLOW DISABLED
|
||||
# define MAIN_LOOP_RATE 400
|
||||
#endif
|
||||
|
||||
#if MAIN_LOOP_RATE == 400
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
# define MAIN_LOOP_RATE 400
|
||||
# define MAIN_LOOP_SECONDS 0.0025
|
||||
# define MAIN_LOOP_MICROS 2500
|
||||
#else
|
||||
# define MAIN_LOOP_RATE 100
|
||||
# define MAIN_LOOP_SECONDS 0.01
|
||||
# define MAIN_LOOP_MICROS 10000
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user