Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
cc2500_compat.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
3  *
4  * This code is based on the betaflight cc2500 and FrskyX implementation.
5  * https://github.com/betaflight/betaflight
6  *
7  * This file is part of paparazzi.
8  *
9  * paparazzi is free software; you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation; either version 2, or (at your option)
12  * any later version.
13  *
14  * paparazzi is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with paparazzi; see the file COPYING. If not, write to
21  * the Free Software Foundation, 59 Temple Place - Suite 330,
22  * Boston, MA 02111-1307, USA.
23  */
24 
25 /*
26  * This file contains compatibility code for the betaflight cc2500 frsky
27  * drivers.
28  *
29  * Notes:
30  * - Function macros are used so that betaflight names can be used when this
31  * header is included, while the actual functions can have a bf_ prefix to
32  * prevent possible name collisions.
33  */
34 
35 #ifndef RADIO_CONTROL_CC2500_COMPAT_H
36 #define RADIO_CONTROL_CC2500_COMPAT_H
37 
38 
39 #pragma GCC diagnostic ignored "-Wmissing-prototypes"
40 #pragma GCC diagnostic ignored "-Wstrict-prototypes"
41 #pragma GCC diagnostic ignored "-Wswitch-default"
42 #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
43 #pragma GCC diagnostic ignored "-Wshadow"
44 
45 
46 #include <stdint.h>
47 #include <stdbool.h>
48 #include <stdlib.h>
49 
50 #define USE_RX_SPI
51 #define USE_RX_FRSKY_SPI
52 #define USE_RX_FRSKY_SPI_TELEMETRY
53 
54 #if (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_X_LBT) || (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_X)
55 #define USE_RX_FRSKY_SPI_X
56 #define USE_TELEMETRY_SMARTPORT
57 #endif
58 #if (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_D)
59 #define USE_RX_FRSKY_SPI_D
60 #endif
61 
62 #define DEBUG_SET(...) /* Do nothing */
63 #define STATIC_ASSERT(...) /* Do nothing */
64 #define STATIC_UNIT_TESTED static
65 
66 
67 // (unknown):
68 #define sensors(...) 1
69 
74 };
75 struct attitude_t {
77 };
78 extern struct attitude_t bf_attitude;
79 #define attitude bf_attitude
80 
81 
82 // main/common/utils.h:
83 #if __GNUC__ > 6
84 #define FALLTHROUGH __attribute__ ((fallthrough))
85 #else
86 #define FALLTHROUGH do {} while(0)
87 #endif
88 
89 
90 // main/common/time.h:
92 typedef uint32_t timeMs_t ;
94 #define TIMEUS_MAX UINT32_MAX
95 
96 static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }
97 
98 
99 // main/common/maths.h:
100 #define MIN(a,b) \
101  __extension__ ({ __typeof__ (a) _a = (a); \
102  __typeof__ (b) _b = (b); \
103  _a < _b ? _a : _b; })
104 
105 
106 // main/common/filter.h:
107 typedef struct pt1Filter_s {
108  float state;
109  float k;
111 
112 float pt1FilterGain(float f_cut, float dT);
113 void pt1FilterInit(pt1Filter_t *filter, float k);
114 void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k);
115 float pt1FilterApply(pt1Filter_t *filter, float input);
116 
117 
118 // main/config/config.h:
119 #define PID_ROLL 0
120 #define PID_PITCH 0
121 #define PID_YAW 0
122 
123 struct pidGains_s {
127 };
128 struct pidProfile_s {
129  struct pidGains_s pid[1];
130 };
131 extern struct pidProfile_s *currentPidProfile;
132 
133 
134 // main/config/feature.h:
135 typedef enum {
136  FEATURE_RX_PPM = 1 << 0,
137 // FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
139 // FEATURE_MOTOR_STOP = 1 << 4,
140 // FEATURE_SERVO_TILT = 1 << 5,
141 // FEATURE_SOFTSERIAL = 1 << 6,
142 // FEATURE_GPS = 1 << 7,
143 // FEATURE_RANGEFINDER = 1 << 9,
144  FEATURE_TELEMETRY = 1 << 10,
145 // FEATURE_3D = 1 << 12,
147  FEATURE_RX_MSP = 1 << 14,
148  FEATURE_RSSI_ADC = 1 << 15,
149 // FEATURE_LED_STRIP = 1 << 16,
150 // FEATURE_DASHBOARD = 1 << 17,
151 // FEATURE_OSD = 1 << 18,
152 // FEATURE_CHANNEL_FORWARDING = 1 << 20,
153 // FEATURE_TRANSPONDER = 1 << 21,
154 // FEATURE_AIRMODE = 1 << 22,
155  FEATURE_RX_SPI = 1 << 25,
156 // //FEATURE_SOFTSPI = 1 << 26, (removed)
157 // FEATURE_ESC_SENSOR = 1 << 27,
158 // FEATURE_ANTI_GRAVITY = 1 << 28,
159 // FEATURE_DYNAMIC_FILTER = 1 << 29,
160 } features_e;
161 
162 bool bf_featureIsEnabled(const uint32_t mask);
163 #define featureIsEnabled(mask) bf_featureIsEnabled(mask)
164 
165 
166 // main/drivers/time.h:
168 #define delayMicroseconds(us) bf_delayMicroseconds(us)
169 
170 void bf_delay(timeMs_t ms);
171 #define delay(ms) bf_delay(ms)
172 
173 timeUs_t bf_micros(void);
174 #define micros() bf_micros()
175 timeMs_t bf_millis(void);
176 #define millis() bf_millis()
177 
178 
179 // main/drivers/adc.h:
180 #define ADC_EXTERNAL1 1
182 #define adcGetChannel(channel) bf_adcGetChannel(channel)
183 
184 
185 // main/drivers/rx/rx_spi.h:
186 #define RX_SPI_MAX_PAYLOAD_SIZE 35
187 
188 bool bf_rxSpiDeviceInit(void);
189 #define rxSpiDeviceInit(rxSpiConfig) bf_rxSpiDeviceInit()
190 
191 
192 // main/drivers/rx/rx_pwm.h:
193 #define PPM_RCVR_TIMEOUT 0
194 
195 
196 // main/drivers/io.h:
197 typedef void(*gpiofnptr_t)(uint32_t port, uint16_t pin);
198 
199 struct gpio_t {
204 };
205 typedef struct gpio_t *IO_t;
206 typedef IO_t ioTag_t;
207 #define IO_NONE NULL
208 
210 #define IOGetByTag(io) bf_IOGetByTag(io)
211 
212 void bf_IOInit(IO_t io, uint8_t owner, uint8_t index);
213 #define IOInit(io, owner, index) bf_IOInit(io, owner, index)
214 
219 };
220 void bf_IOConfigGPIO(IO_t io, enum ioconfig_t cfg);
221 #define IOConfigGPIO(io, cfg) bf_IOConfigGPIO(io, cfg)
222 
223 bool bf_IORead(IO_t gpio);
224 #define IORead(gpio) bf_IORead(gpio)
225 
226 void bf_IOHi(IO_t io);
227 #define IOHi(io) bf_IOHi(io)
228 void bf_IOLo(IO_t io);
229 #define IOLo(io) bf_IOLo(io)
230 void bf_IOToggle(IO_t io);
231 #define IOToggle(io) bf_IOToggle(io)
232 
233 
234 // main/fc/runtime_config.h:
235 #define isArmingDisabled() 0
236 #define ARMING_FLAG(...) 1
237 #define FLIGHT_MODE(...) 0
238 
239 
240 // main/fc/controlrate_profile.h:
241 #define FD_ROLL 0
242 #define FD_PITCH 0
243 #define FD_YAW 0
244 typedef struct {
245  uint8_t rates[1];
248 
249 
250 // main/flight/position.h:
252 #define getEstimatedAltitudeCm() bf_getEstimatedAltitudeCm()
253 
255 #define getEstimatedVario() bf_getEstimatedVario()
256 
257 
258 // main/drivers/resources.h:
259 typedef enum {
264 
265 
266 // main/sensors/battery.h
268 #define isBatteryVoltageConfigured() bf_isBatteryVoltageConfigured()
269 
271 #define getLegacyBatteryVoltage() bf_getLegacyBatteryVoltage()
273 #define getBatteryVoltage() bf_getBatteryVoltage()
274 
276 #define getBatteryCellCount() bf_getBatteryCellCount()
277 
278 bool bf_isAmperageConfigured(void);
279 #define isAmperageConfigured() bf_isAmperageConfigured()
280 int32_t bf_getAmperage(void);
281 #define getAmperage() bf_getAmperage()
282 int32_t bf_getMAhDrawn(void);
283 #define getMAhDrawn() bf_getMAhDrawn()
284 
285 
286 #endif // RADIO_CONTROL_CC2500_COMPAT_H
ioconfig_t
@ IOCFG_IN_FLOATING
@ IOCFG_IPU
@ IOCFG_OUT_PP
struct pt1Filter_s pt1Filter_t
void pt1FilterInit(pt1Filter_t *filter, float k)
Definition: cc2500_compat.c:61
bool bf_isAmperageConfigured(void)
gpiofnptr_t lo
bool bf_isBatteryVoltageConfigured(void)
void bf_delayMicroseconds(timeUs_t us)
Definition: cc2500_compat.c:77
int32_t bf_getEstimatedAltitudeCm(void)
void bf_IOLo(IO_t io)
uint16_t bf_getBatteryVoltage(void)
uint32_t timeMs_t
Definition: cc2500_compat.h:92
resourceOwner_e
@ OWNER_RX_SPI_BIND
@ OWNER_RX_SPI_EXTI
@ OWNER_LED
uint32_t port
int32_t timeDelta_t
Definition: cc2500_compat.h:91
bool bf_rxSpiDeviceInit(void)
struct attitude_values_t values
Definition: cc2500_compat.h:76
struct pidProfile_s * currentPidProfile
Definition: cc2500_compat.c:43
IO_t ioTag_t
struct gpio_t * IO_t
void(* gpiofnptr_t)(uint32_t port, uint16_t pin)
timeUs_t bf_micros(void)
Definition: cc2500_compat.c:85
struct attitude_t bf_attitude
Definition: cc2500_compat.c:39
uint16_t pin
int32_t bf_getAmperage(void)
gpiofnptr_t hi
struct pidGains_s pid[1]
uint16_t bf_adcGetChannel(uint8_t channel)
Definition: cc2500_compat.c:95
int32_t bf_getMAhDrawn(void)
timeMs_t bf_millis(void)
Definition: cc2500_compat.c:89
static timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b)
Definition: cc2500_compat.h:96
uint8_t bf_getBatteryCellCount(void)
IO_t bf_IOGetByTag(ioTag_t io)
float pt1FilterGain(float f_cut, float dT)
Definition: cc2500_compat.c:55
uint32_t timeUs_t
Definition: cc2500_compat.h:93
features_e
@ FEATURE_RX_SPI
@ FEATURE_RX_PARALLEL_PWM
@ FEATURE_TELEMETRY
@ FEATURE_RX_PPM
@ FEATURE_RX_SERIAL
@ FEATURE_RX_MSP
@ FEATURE_RSSI_ADC
bool bf_IORead(IO_t gpio)
int16_t bf_getEstimatedVario(void)
void bf_IOInit(IO_t io, uint8_t owner, uint8_t index)
void bf_delay(timeMs_t ms)
Definition: cc2500_compat.c:81
void bf_IOHi(IO_t io)
void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k)
Definition: cc2500_compat.c:66
void bf_IOToggle(IO_t io)
uint16_t bf_getLegacyBatteryVoltage(void)
float pt1FilterApply(pt1Filter_t *filter, float input)
Definition: cc2500_compat.c:70
void bf_IOConfigGPIO(IO_t io, enum ioconfig_t cfg)
bool bf_featureIsEnabled(const uint32_t mask)
Definition: cc2500_compat.c:47
controlRateConfig_t * currentControlRateProfile
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
Definition: vl53l1_types.h:88
int int32_t
Typedef defining 32 bit int type.
Definition: vl53l1_types.h:83
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
Definition: vl53l1_types.h:78
short int16_t
Typedef defining 16 bit short type.
Definition: vl53l1_types.h:93
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98
signed char int8_t
Typedef defining 8 bit char type.
Definition: vl53l1_types.h:103
float b
Definition: wedgebug.c:202