Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
cc2500_settings.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 #ifndef RADIO_CONTROL_CC2500_SETTINGS_H
26 #define RADIO_CONTROL_CC2500_SETTINGS_H
27 
28 #include "cc2500_compat.h"
29 
30 #include <stdint.h>
31 
32 /* Paparazzi settings */
33 void cc2500_settings_init(void);
34 
38 };
40 
41 
42 /* betaflight settings API */
43 // main/config/config.h:
44 void bf_writeEEPROM(void);
45 #define writeEEPROM() bf_writeEEPROM()
46 
47 
48 // main/pg/rx.h:
49 #define FRAME_ERR_RESAMPLE_US 100000
50 
51 #define GET_FRAME_ERR_LPF_FREQUENCY(period) (1 / (period / 10.0f))
52 
53 typedef struct rxConfig_s {
54 // uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
55  uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
56 // uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
57 // uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
58 // ioTag_t spektrum_bind_pin_override_ioTag;
59 // ioTag_t spektrum_bind_plug_ioTag;
60 // uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
61 // uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
63 // uint8_t rssi_scale;
64 // uint8_t rssi_invert;
65  uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
66 // uint16_t mincheck; // minimum rc end
67 // uint16_t maxcheck; // maximum rc end
68 // uint8_t rcInterpolation;
69 // uint8_t rcInterpolationChannels;
70 // uint8_t rcInterpolationInterval;
71 // uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
72 // uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
73 //
74 // uint16_t rx_min_usec;
75 // uint16_t rx_max_usec;
77 // uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol
78 // int8_t rssi_offset; // offset applied to the RSSI value before it is returned
79 // uint8_t rc_smoothing_type; // Determines the smoothing algorithm to use: INTERPOLATION or FILTER
80 // uint8_t rc_smoothing_input_cutoff; // Filter cutoff frequency for the input filter (0 = auto)
81 // uint8_t rc_smoothing_derivative_cutoff; // Filter cutoff frequency for the setpoint weight derivative filter (0 = auto)
82 // uint8_t rc_smoothing_debug_axis; // Axis to log as debug values when debug_mode = RC_SMOOTHING
83 // uint8_t rc_smoothing_input_type; // Input filter type (0 = PT1, 1 = BIQUAD)
84 // uint8_t rc_smoothing_derivative_type; // Derivative filter type (0 = OFF, 1 = PT1, 2 = BIQUAD)
85 // uint8_t rc_smoothing_auto_factor; // Used to adjust the "smoothness" determined by the auto cutoff calculations
86  uint8_t rssi_src_frame_lpf_period; // Period of the cutoff frequency for the source frame RSSI filter (in 0.1 s)
87 //
88 // uint8_t srxl2_unit_id; // Spektrum SRXL2 RX unit id
89 // uint8_t srxl2_baud_fast; // Select Spektrum SRXL2 fast baud rate
90 // uint8_t sbus_baud_fast; // Select SBus fast baud rate
92 
93 const rxConfig_t* rxConfig(void);
94 
95 // main/pg/rx_spi.h:
96 typedef struct rxSpiConfig_s {
97  // RX protocol
98  uint8_t rx_spi_protocol; // type of SPI RX protocol
99 // // nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.)
100 // uint32_t rx_spi_id;
101 // uint8_t rx_spi_rf_channel_count;
102 //
103 // // SPI Bus
104 // ioTag_t csnTag;
105 // uint8_t spibus;
106 //
110 
113 
114 const rxSpiConfig_t* rxSpiConfig(void);
115 
116 
117 // main/pg/rx_spi_cc2500.h:
118 typedef enum {
123 
124 typedef struct rxCc2500SpiConfig_s {
132 // ioTag_t txEnIoTag;
133 // ioTag_t lnaEnIoTag;
134 // ioTag_t antSelIoTag;
136 
139 
140 
141 // main/telemetry/telemetry.h:
142 typedef struct telemetryConfig_s {
143 // int16_t gpsNoFixLatitude;
144 // int16_t gpsNoFixLongitude;
145 // uint8_t telemetry_inverted;
146 // uint8_t halfDuplex;
147 // frskyGpsCoordFormat_e frsky_coordinate_format;
148 // frskyUnit_e frsky_unit;
149 // uint8_t frsky_vfas_precision;
150 // uint8_t hottAlarmSoundInterval;
153 // uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
154 // uint16_t mavlink_mah_as_heading_divisor;
155 // uint32_t disabledSensors; // bit flags
157 
159 
160 typedef enum {
161  SENSOR_VOLTAGE = 1 << 0,
162  SENSOR_CURRENT = 1 << 1,
163  SENSOR_FUEL = 1 << 2,
164  SENSOR_MODE = 1 << 3,
165  SENSOR_ACC_X = 1 << 4,
166  SENSOR_ACC_Y = 1 << 5,
167  SENSOR_ACC_Z = 1 << 6,
168  SENSOR_PITCH = 1 << 7,
169  SENSOR_ROLL = 1 << 8,
170  SENSOR_HEADING = 1 << 9,
171  SENSOR_ALTITUDE = 1 << 10,
172  SENSOR_VARIO = 1 << 11,
173  SENSOR_LAT_LONG = 1 << 12,
175  SENSOR_DISTANCE = 1 << 14,
178  ESC_SENSOR_RPM = 1 << 17,
182  | ESC_SENSOR_RPM \
185  SENSOR_ALL = (1 << 20) - 1,
186 } sensor_e;
187 #define SENSOR_NONE 0
188 
190 
191 
192 #endif // RADIO_CONTROL_CC2500_SETTINGS_H
void cc2500_settings_init(void)
uint8_t serialrx_provider
uint8_t rssi_src_frame_lpf_period
sensor_e
@ SENSOR_ALL
@ SENSOR_CURRENT
@ SENSOR_VOLTAGE
@ SENSOR_DISTANCE
@ ESC_SENSOR_VOLTAGE
@ SENSOR_PITCH
@ SENSOR_ROLL
@ SENSOR_VARIO
@ SENSOR_ACC_Y
@ ESC_SENSOR_CURRENT
@ SENSOR_GROUND_SPEED
@ SENSOR_MODE
@ SENSOR_FUEL
@ ESC_SENSOR_ALL
@ SENSOR_ACC_X
@ SENSOR_ACC_Z
@ ESC_SENSOR_TEMPERATURE
@ SENSOR_TEMPERATURE
@ ESC_SENSOR_RPM
@ SENSOR_LAT_LONG
@ SENSOR_ALTITUDE
@ SENSOR_HEADING
uint16_t midrc
uint8_t ledInversion
uint8_t rssi_channel
uint8_t pidValuesAsTelemetry
const rxSpiConfig_t * rxSpiConfig(void)
frSkySpiA1Source_e
@ FRSKY_SPI_A1_SOURCE_CONST
@ FRSKY_SPI_A1_SOURCE_VBAT
@ FRSKY_SPI_A1_SOURCE_EXTADC
const telemetryConfig_t * telemetryConfig(void)
bool telemetryIsSensorEnabled(sensor_e sensor)
struct rxConfig_s rxConfig_t
void bf_writeEEPROM(void)
uint8_t rx_spi_protocol
struct telemetryConfig_s telemetryConfig_t
const rxCc2500SpiConfig_t * rxCc2500SpiConfig(void)
struct cc2500_settings_persistent_s cc2500_settings_persistent
uint8_t max_aux_channel
struct rxSpiConfig_s rxSpiConfig_t
rxCc2500SpiConfig_t * rxCc2500SpiConfigMutable(void)
const rxConfig_t * rxConfig(void)
struct rxCc2500SpiConfig_s rxCc2500SpiConfig_t
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
Definition: vl53l1_types.h:88
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
Definition: vl53l1_types.h:78
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