2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 // SITL (software in the loop) simulator
28 #include "common/utils.h"
30 #define TARGET_BOARD_IDENTIFIER "SITL"
32 #define SIMULATOR_MULTITHREAD
34 #define SYSTEM_HSE_MHZ 0
35 #define DEFAULT_CPU_OVERCLOCK 1
42 #define DMA_DATA_ZERO_INIT
44 #define STATIC_DMA_DATA_AUTO
46 // use simulatior's attitude directly
47 // disable this if wants to test AHRS algorithm
50 //#define SIMULATOR_ACC_SYNC
51 //#define SIMULATOR_GYRO_SYNC
52 //#define SIMULATOR_IMU_SYNC
53 //#define SIMULATOR_GYROPID_SYNC
55 // file name to save config
56 #define EEPROM_FILENAME "eeprom.bin"
57 #define CONFIG_IN_FILE
58 #define EEPROM_SIZE 32768
64 #undef TASK_GYROPID_DESIRED_PERIOD
65 #define TASK_GYROPID_DESIRED_PERIOD 100
67 #undef SCHEDULER_DELAY_LIMIT
68 #define SCHEDULER_DELAY_LIMIT 1
70 #define USE_VIRTUAL_LED
73 #define USE_VIRTUAL_ACC
76 #define USE_VIRTUAL_GYRO
79 #define USE_VIRTUAL_MAG
82 #define USE_VIRTUAL_BARO
84 #define USABLE_TIMER_CHANNEL_COUNT 0
95 #define SERIAL_PORT_COUNT 8
97 #define DEFAULT_RX_FEATURE FEATURE_RX_MSP
98 #define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_TELEMETRY)
100 #define USE_PARAMETER_GROUPS
102 #define USE_PWM_OUTPUT
104 #undef USE_STACK_CHECK // I think SITL don't need this
106 #undef USE_TELEMETRY_LTM
113 #undef USE_SERIALRX_CRSF
114 #undef USE_SERIALRX_GHST
115 #undef USE_SERIALRX_IBUS
116 #undef USE_SERIALRX_SBUS
117 #undef USE_SERIALRX_SPEKTRUM
118 #undef USE_SERIALRX_SUMD
119 #undef USE_SERIALRX_SUMH
120 #undef USE_SERIALRX_XBUS
122 #undef USE_TELEMETRY_FRSKY_HUB
123 #undef USE_TELEMETRY_HOTT
124 #undef USE_TELEMETRY_SMARTPORT
125 #undef USE_TELEMETRY_MAVLINK
126 #undef USE_RESOURCE_MGMT
128 #undef USE_TELEMETRY_CRSF
129 #undef USE_TELEMETRY_GHST
130 #undef USE_TELEMETRY_IBUS
131 #undef USE_TELEMETRY_JETIEXBUS
132 #undef USE_TELEMETRY_SRXL
133 #undef USE_SERIALRX_JETIEXBUS
134 #undef USE_VTX_COMMON
135 #undef USE_VTX_CONTROL
136 #undef USE_VTX_SMARTAUDIO
139 #undef USE_CAMERA_CONTROL
140 #undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
141 #undef USE_SERIAL_4WAY_SK_BOOTLOADER
146 #define TARGET_FLASH_SIZE 2048
149 #define LED_STRIP_TIMER 1
150 #define SOFTSERIAL_1_TIMER 2
151 #define SOFTSERIAL_2_TIMER 3
153 #define DEFIO_NO_PORTS // suppress 'no pins defined' warning
155 #define FLASH_PAGE_SIZE (0x400)
157 // belows are internal stuff
159 extern uint32_t SystemCoreClock
;
167 typedef enum {RESET
= 0, SET
= !RESET
} FlagStatus
, ITStatus
;
168 typedef enum {DISABLE
= 0, ENABLE
= !DISABLE
} FunctionalState
;
169 typedef enum {TEST_IRQ
= 0 } IRQn_Type
;
171 EXTI_Trigger_Rising
= 0x08,
172 EXTI_Trigger_Falling
= 0x0C,
173 EXTI_Trigger_Rising_Falling
= 0x10
174 } EXTITrigger_TypeDef
;
184 #define GPIOA_BASE ((intptr_t)0x0001)
202 } DMA_Channel_TypeDef
;
208 uint8_t DMA_GetFlagStatus(void *);
209 void DMA_Cmd(DMA_Channel_TypeDef
*, FunctionalState
);
210 void DMA_ClearFlag(uint32_t);
222 #define USART1 ((USART_TypeDef *)0x0001)
223 #define USART2 ((USART_TypeDef *)0x0002)
224 #define USART3 ((USART_TypeDef *)0x0003)
225 #define USART4 ((USART_TypeDef *)0x0004)
226 #define USART5 ((USART_TypeDef *)0x0005)
227 #define USART6 ((USART_TypeDef *)0x0006)
228 #define USART7 ((USART_TypeDef *)0x0007)
229 #define USART8 ((USART_TypeDef *)0x0008)
231 #define UART4 ((USART_TypeDef *)0x0004)
232 #define UART5 ((USART_TypeDef *)0x0005)
233 #define UART7 ((USART_TypeDef *)0x0007)
234 #define UART8 ((USART_TypeDef *)0x0008)
236 #define SIMULATOR_MAX_RC_CHANNELS 16
237 #define SIMULATOR_MAX_PWM_CHANNELS 16
254 double timestamp
; // in seconds
255 double imu_angular_velocity_rpy
[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se
256 double imu_linear_acceleration_xyz
[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256
257 double imu_orientation_quat
[4]; //w, x, y, z
258 double velocity_xyz
[3]; // m/s, earth frame
259 double position_xyz
[3]; // meters, NED from origin
264 double timestamp
; // in seconds
265 uint16_t channels
[SIMULATOR_MAX_RC_CHANNELS
]; // RC channels
269 float motor_speed
[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
273 uint16_t motorCount
; // Count of motor in the PWM output.
274 float pwm_output_raw
[SIMULATOR_MAX_PWM_CHANNELS
]; // Raw PWM from 1100 to 1900
277 void FLASH_Unlock(void);
278 void FLASH_Lock(void);
279 FLASH_Status
FLASH_ErasePage(uintptr_t Page_Address
);
280 FLASH_Status
FLASH_ProgramWord(uintptr_t addr
, uint32_t Data
);
282 uint64_t nanos64_real(void);
283 uint64_t micros64_real(void);
284 uint64_t millis64_real(void);
285 void delayMicroseconds_real(uint32_t us
);
286 uint64_t micros64(void);
287 uint64_t millis64(void);
289 int lockMainPID(void);
291 int targetParseArgs(int argc
, char * argv
[]);