Naming adjustment for USE_SERIAL_RX to USE_SERIALRX (#11992)
[betaflight.git] / src / main / target / SITL / target.h
blob917ab77b69292388e356de4f7bb6593d048069a4
1 /*
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)
8 * any later version.
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
23 #pragma once
25 #include <stdint.h>
26 #include <stddef.h>
28 #include "common/utils.h"
30 #define TARGET_BOARD_IDENTIFIER "SITL"
32 #define SIMULATOR_MULTITHREAD
34 // use simulatior's attitude directly
35 // disable this if wants to test AHRS algorithm
36 #undef USE_IMU_CALC
38 //#define SIMULATOR_ACC_SYNC
39 //#define SIMULATOR_GYRO_SYNC
40 //#define SIMULATOR_IMU_SYNC
41 //#define SIMULATOR_GYROPID_SYNC
43 // file name to save config
44 #define EEPROM_FILENAME "eeprom.bin"
45 #define CONFIG_IN_FILE
46 #define EEPROM_SIZE 32768
48 #define U_ID_0 0
49 #define U_ID_1 1
50 #define U_ID_2 2
52 #undef TASK_GYROPID_DESIRED_PERIOD
53 #define TASK_GYROPID_DESIRED_PERIOD 100
55 #undef SCHEDULER_DELAY_LIMIT
56 #define SCHEDULER_DELAY_LIMIT 1
58 #define USE_FAKE_LED
60 #define USE_ACC
61 #define USE_FAKE_ACC
63 #define USE_GYRO
64 #define USE_FAKE_GYRO
66 #define USE_MAG
67 #define USE_FAKE_MAG
69 #define USE_BARO
70 #define USE_FAKE_BARO
72 #define USABLE_TIMER_CHANNEL_COUNT 0
74 #define USE_UART1
75 #define USE_UART2
76 #define USE_UART3
77 #define USE_UART4
78 #define USE_UART5
79 #define USE_UART6
80 #define USE_UART7
81 #define USE_UART8
83 //#define USE_SOFTSERIAL1
84 //#define USE_SOFTSERIAL2
86 #define SERIAL_PORT_COUNT 8
88 #define DEFAULT_RX_FEATURE FEATURE_RX_MSP
89 #define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_TELEMETRY)
91 #define USE_PARAMETER_GROUPS
93 #undef USE_STACK_CHECK // I think SITL don't need this
94 #undef USE_DASHBOARD
95 #undef USE_TELEMETRY_LTM
96 #undef USE_ADC
97 #undef USE_VCP
98 #undef USE_OSD
99 #undef USE_PPM
100 #undef USE_PWM
101 #undef USE_SERIALRX
102 #undef USE_SERIALRX_CRSF
103 #undef USE_SERIALRX_GHST
104 #undef USE_SERIALRX_IBUS
105 #undef USE_SERIALRX_SBUS
106 #undef USE_SERIALRX_SPEKTRUM
107 #undef USE_SERIALRX_SUMD
108 #undef USE_SERIALRX_SUMH
109 #undef USE_SERIALRX_XBUS
110 #undef USE_LED_STRIP
111 #undef USE_TELEMETRY_FRSKY_HUB
112 #undef USE_TELEMETRY_HOTT
113 #undef USE_TELEMETRY_SMARTPORT
114 #undef USE_TELEMETRY_MAVLINK
115 #undef USE_RESOURCE_MGMT
116 #undef USE_CMS
117 #undef USE_TELEMETRY_CRSF
118 #undef USE_TELEMETRY_GHST
119 #undef USE_TELEMETRY_IBUS
120 #undef USE_TELEMETRY_JETIEXBUS
121 #undef USE_TELEMETRY_SRXL
122 #undef USE_SERIALRX_JETIEXBUS
123 #undef USE_VTX_COMMON
124 #undef USE_VTX_CONTROL
125 #undef USE_VTX_SMARTAUDIO
126 #undef USE_VTX_TRAMP
127 #undef USE_VTX_MSP
128 #undef USE_CAMERA_CONTROL
129 #undef USE_BRUSHED_ESC_AUTODETECT
130 #undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
131 #undef USE_SERIAL_4WAY_SK_BOOTLOADER
133 #undef USE_I2C
134 #undef USE_SPI
136 #define TARGET_FLASH_SIZE 2048
139 #define LED_STRIP_TIMER 1
140 #define SOFTSERIAL_1_TIMER 2
141 #define SOFTSERIAL_2_TIMER 3
143 #define DEFIO_NO_PORTS // suppress 'no pins defined' warning
145 // belows are internal stuff
147 extern uint32_t SystemCoreClock;
149 typedef enum
151 Mode_TEST = 0x0,
152 Mode_Out_PP = 0x10
153 } GPIO_Mode;
155 typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
156 typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
157 typedef enum {TEST_IRQ = 0 } IRQn_Type;
158 typedef enum {
159 EXTI_Trigger_Rising = 0x08,
160 EXTI_Trigger_Falling = 0x0C,
161 EXTI_Trigger_Rising_Falling = 0x10
162 } EXTITrigger_TypeDef;
164 typedef struct
166 uint32_t IDR;
167 uint32_t ODR;
168 uint32_t BSRR;
169 uint32_t BRR;
170 } GPIO_TypeDef;
172 #define GPIOA_BASE ((intptr_t)0x0001)
174 typedef struct
176 void* test;
177 } TIM_TypeDef;
179 typedef struct
181 void* test;
182 } TIM_OCInitTypeDef;
184 typedef struct {
185 void* test;
186 } DMA_TypeDef;
188 typedef struct {
189 void* test;
190 } DMA_Channel_TypeDef;
192 typedef struct {
193 void* test;
194 } DMA_InitTypeDef;
196 uint8_t DMA_GetFlagStatus(void *);
197 void DMA_Cmd(DMA_Channel_TypeDef*, FunctionalState );
198 void DMA_ClearFlag(uint32_t);
200 typedef struct
202 void* test;
203 } SPI_TypeDef;
205 typedef struct
207 void* test;
208 } USART_TypeDef;
210 #define USART1 ((USART_TypeDef *)0x0001)
211 #define USART2 ((USART_TypeDef *)0x0002)
212 #define USART3 ((USART_TypeDef *)0x0003)
213 #define USART4 ((USART_TypeDef *)0x0004)
214 #define USART5 ((USART_TypeDef *)0x0005)
215 #define USART6 ((USART_TypeDef *)0x0006)
216 #define USART7 ((USART_TypeDef *)0x0007)
217 #define USART8 ((USART_TypeDef *)0x0008)
219 #define UART4 ((USART_TypeDef *)0x0004)
220 #define UART5 ((USART_TypeDef *)0x0005)
221 #define UART7 ((USART_TypeDef *)0x0007)
222 #define UART8 ((USART_TypeDef *)0x0008)
224 typedef struct
226 void* test;
227 } I2C_TypeDef;
229 typedef enum
231 FLASH_BUSY = 1,
232 FLASH_ERROR_PG,
233 FLASH_ERROR_WRP,
234 FLASH_COMPLETE,
235 FLASH_TIMEOUT
236 } FLASH_Status;
238 typedef struct {
239 double timestamp; // in seconds
240 double imu_angular_velocity_rpy[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se
241 double imu_linear_acceleration_xyz[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256
242 double imu_orientation_quat[4]; //w, x, y, z
243 double velocity_xyz[3]; // m/s, earth frame
244 double position_xyz[3]; // meters, NED from origin
245 } fdm_packet;
246 typedef struct {
247 float motor_speed[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
248 } servo_packet;
250 void FLASH_Unlock(void);
251 void FLASH_Lock(void);
252 FLASH_Status FLASH_ErasePage(uintptr_t Page_Address);
253 FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t Data);
255 uint64_t nanos64_real(void);
256 uint64_t micros64_real(void);
257 uint64_t millis64_real(void);
258 void delayMicroseconds_real(uint32_t us);
259 uint64_t micros64(void);
260 uint64_t millis64(void);
262 int lockMainPID(void);