Create a pg for rxConfig

This commit is contained in:
jflyper 2018-05-25 11:01:49 +09:00
parent 60de878452
commit 041bfb22c6
99 changed files with 320 additions and 101 deletions

View File

@ -45,6 +45,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/compass/compass.h"
#include "drivers/sensor.h"

View File

@ -54,6 +54,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
// For 'ARM' related
#include "fc/config.h"

View File

@ -41,6 +41,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "fc/config.h"
#include "fc/rc_controls.h"

View File

@ -31,6 +31,8 @@
#include "build/build_config.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/rx/rx_spi.h"
#include "drivers/system.h"

View File

@ -31,6 +31,8 @@
#include "build/build_config.h"
#include "pg/rx.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"

View File

@ -24,8 +24,12 @@
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "common/crc.h"
#include "pg/rx.h"
#include "drivers/rx/rx_nrf24l01.h"
#include "drivers/rx/rx_spi.h"

View File

@ -51,6 +51,7 @@
#include "pg/beeper.h"
#include "pg/beeper_dev.h"
#include "pg/rx.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"

View File

@ -37,6 +37,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/light_led.h"
#include "drivers/serial_usb_vcp.h"

View File

@ -97,6 +97,7 @@
#include "pg/pinio.h"
#include "pg/piniobox.h"
#include "pg/pg.h"
#include "pg/rx.h"
#include "pg/rx_pwm.h"
#include "pg/sdcard.h"
#include "pg/vcd.h"

View File

@ -44,8 +44,10 @@
#include "flight/imu.h"
#include "flight/gps_rescue.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/battery.h"
typedef float (applyRatesFn)(const int axis, float rcCommandf, const float rcCommandfAbs);

View File

@ -73,6 +73,8 @@
#include "msp/msp_serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/acceleration.h"

View File

@ -37,9 +37,10 @@
#include "drivers/time.h"
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "config/feature.h"
#include "pg/rx.h"
#include "flight/pid.h"

View File

@ -36,6 +36,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "cms/cms.h"

View File

@ -32,6 +32,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "fc/config.h"
#include "fc/rc_controls.h"

View File

@ -29,6 +29,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/time.h"

View File

@ -35,6 +35,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_esc_detect.h"

View File

@ -36,6 +36,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/pwm_output.h"

View File

@ -126,6 +126,7 @@ extern uint8_t __config_end;
#include "pg/pinio.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "pg/rx_pwm.h"
#include "pg/timerio.h"
#include "pg/usb.h"

View File

@ -44,6 +44,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/beeper.h"
#include "pg/rx.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/bus_i2c.h"

View File

@ -75,6 +75,7 @@
#include "pg/pg_ids.h"
#include "pg/pinio.h"
#include "pg/piniobox.h"
#include "pg/rx.h"
#include "pg/rx_pwm.h"
#include "pg/sdcard.h"
#include "pg/vcd.h"

View File

@ -50,6 +50,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/dashboard.h"
#include "pg/rx.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"

View File

@ -40,6 +40,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/light_ws2811strip.h"
#include "drivers/serial.h"

View File

@ -82,6 +82,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "rx/rx.h"

View File

@ -21,6 +21,10 @@
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "pg/rx.h"
#include "drivers/time.h"
#include "cms/cms.h"

View File

@ -29,6 +29,8 @@
#include "drivers/system.h"
#include "drivers/time.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/spektrum.h"
#include "io/spektrum_rssi.h"

72
src/main/pg/rx.c Normal file
View File

@ -0,0 +1,72 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#if defined(USE_PWM) || defined(USE_PPM) || defined(USE_SERIAL_RX) || defined(USE_RX_MSP)
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "rx.h"
#include "config/config_reset.h"
#include "drivers/io.h"
#include "fc/rc_controls.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 2);
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
{
RESET_CONFIG_2(rxConfig_t, rxConfig,
.halfDuplex = 0,
.serialrx_provider = SERIALRX_PROVIDER,
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
.serialrx_inverted = 0,
.spektrum_bind_pin_override_ioTag = IO_TAG(SPEKTRUM_BIND_PIN),
.spektrum_bind_plug_ioTag = IO_TAG(BINDPLUG_PIN),
.spektrum_sat_bind = 0,
.spektrum_sat_bind_autoreset = 1,
.midrc = RX_MID_USEC,
.mincheck = 1050,
.maxcheck = 1900,
.rx_min_usec = RX_MIN_USEC, // any of first 4 channels below this value will trigger rx loss detection
.rx_max_usec = RX_MAX_USEC, // any of first 4 channels above this value will trigger rx loss detection
.rssi_src_frame_errors = false,
.rssi_channel = 0,
.rssi_scale = RSSI_SCALE_DEFAULT,
.rssi_invert = 0,
.rcInterpolation = RC_SMOOTHING_AUTO,
.rcInterpolationChannels = 0,
.rcInterpolationInterval = 19,
.fpvCamAngleDegrees = 0,
.airModeActivateThreshold = 32,
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT
);
#ifdef RX_CHANNELS_TAER
parseRcChannels("TAER1234", rxConfig);
#else
parseRcChannels("AETR1234", rxConfig);
#endif
}
#endif

58
src/main/pg/rx.h Normal file
View File

@ -0,0 +1,58 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/io_types.h"
#include "pg/pg.h"
typedef struct rxConfig_s {
uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
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.
uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
uint8_t rx_spi_protocol; // type of SPI RX protocol
// nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.)
uint32_t rx_spi_id;
uint8_t rx_spi_rf_channel_count;
ioTag_t spektrum_bind_pin_override_ioTag;
ioTag_t spektrum_bind_plug_ioTag;
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
uint8_t rssi_channel;
uint8_t rssi_scale;
uint8_t rssi_invert;
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
uint16_t mincheck; // minimum rc end
uint16_t maxcheck; // maximum rc end
uint8_t rcInterpolation;
uint8_t rcInterpolationChannels;
uint8_t rcInterpolationInterval;
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
uint16_t rx_min_usec;
uint16_t rx_max_usec;
uint8_t max_aux_channel;
uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);

View File

@ -30,6 +30,8 @@
#include "build/build_config.h"
#include "build/debug.h"
#include "pg/rx.h"
#include "common/maths.h"
#include "common/utils.h"

View File

@ -34,6 +34,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"

View File

@ -28,6 +28,8 @@
#include "build/build_config.h"
#include "build/debug.h"
#include "pg/rx.h"
#include "common/maths.h"
#include "common/utils.h"

View File

@ -34,6 +34,8 @@
#include "common/maths.h"
#include "common/utils.h"
#include "pg/rx.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/system.h"

View File

@ -36,13 +36,14 @@
#include "fc/config.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "rx/flysky_defs.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "sensors/battery.h"
#include "flysky.h"

View File

@ -41,6 +41,8 @@
#include "telemetry/smartport.h"
#endif
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/sbus_channels.h"
#include "rx/fport.h"

View File

@ -33,6 +33,8 @@
#ifdef USE_SERIAL_RX
#include "pg/rx.h"
#include "common/utils.h"
#include "drivers/serial.h"

View File

@ -49,6 +49,8 @@
#include "build/build_config.h"
#include "build/debug.h"
#include "pg/rx.h"
#include "common/utils.h"
#include "drivers/time.h"

View File

@ -28,9 +28,11 @@
#include "common/utils.h"
#include "drivers/io.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/msp.h"
static uint16_t mspFrame[MAX_SUPPORTED_RC_CHANNEL_COUNT];
static bool rxMspFrameDone = false;

View File

@ -31,6 +31,8 @@
#include "build/build_config.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/rx/rx_nrf24l01.h"
#include "drivers/rx/rx_xn297.h"

View File

@ -33,6 +33,8 @@
#include "common/utils.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/rx/rx_nrf24l01.h"
#include "drivers/rx/rx_xn297.h"

View File

@ -31,6 +31,8 @@
#include "common/utils.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/rx/rx_nrf24l01.h"
#include "drivers/time.h"

View File

@ -31,6 +31,8 @@
#include "build/build_config.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/rx/rx_nrf24l01.h"
#include "drivers/time.h"

View File

@ -33,6 +33,8 @@
#include "common/utils.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/rx/rx_nrf24l01.h"
#include "drivers/time.h"

View File

@ -32,6 +32,8 @@
#include "config/feature.h"
#include "pg/rx.h"
#include "drivers/rx/rx_pwm.h"
#include "fc/config.h"

View File

@ -50,6 +50,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/pwm.h"
@ -108,61 +109,6 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
rxRuntimeConfig_t rxRuntimeConfig;
static uint8_t rcSampleIndex = 0;
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
#endif
#ifndef SERIALRX_PROVIDER
#define SERIALRX_PROVIDER 0
#endif
#define RX_MIN_USEC 885
#define RX_MAX_USEC 2115
#define RX_MID_USEC 1500
#ifndef SPEKTRUM_BIND_PIN
#define SPEKTRUM_BIND_PIN NONE
#endif
#ifndef BINDPLUG_PIN
#define BINDPLUG_PIN NONE
#endif
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 2);
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
{
RESET_CONFIG_2(rxConfig_t, rxConfig,
.halfDuplex = 0,
.serialrx_provider = SERIALRX_PROVIDER,
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
.serialrx_inverted = 0,
.spektrum_bind_pin_override_ioTag = IO_TAG(SPEKTRUM_BIND_PIN),
.spektrum_bind_plug_ioTag = IO_TAG(BINDPLUG_PIN),
.spektrum_sat_bind = 0,
.spektrum_sat_bind_autoreset = 1,
.midrc = RX_MID_USEC,
.mincheck = 1050,
.maxcheck = 1900,
.rx_min_usec = RX_MIN_USEC, // any of first 4 channels below this value will trigger rx loss detection
.rx_max_usec = RX_MAX_USEC, // any of first 4 channels above this value will trigger rx loss detection
.rssi_src_frame_errors = false,
.rssi_channel = 0,
.rssi_scale = RSSI_SCALE_DEFAULT,
.rssi_invert = 0,
.rcInterpolation = RC_SMOOTHING_AUTO,
.rcInterpolationChannels = 0,
.rcInterpolationInterval = 19,
.fpvCamAngleDegrees = 0,
.airModeActivateThreshold = 32,
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT
);
#ifdef RX_CHANNELS_TAER
parseRcChannels("TAER1234", rxConfig);
#else
parseRcChannels("AETR1234", rxConfig);
#endif
}
PG_REGISTER_ARRAY_WITH_RESET_FN(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs, PG_RX_CHANNEL_RANGE_CONFIG, 0);
void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t *rxChannelRangeConfigs)
{

View File

@ -84,8 +84,6 @@ extern const char rcChannelLetters[];
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
#define RX_MAPPABLE_CHANNEL_COUNT 8
#define RSSI_SCALE_MIN 1
#define RSSI_SCALE_MAX 255
#define RSSI_SCALE_DEFAULT (4095.0f / 100.0f + 0.5f) // 100% @ 4095
@ -120,39 +118,6 @@ typedef struct rxChannelRangeConfig_s {
PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
typedef struct rxConfig_s {
uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
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.
uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
uint8_t rx_spi_protocol; // type of SPI RX protocol
// nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.)
uint32_t rx_spi_id;
uint8_t rx_spi_rf_channel_count;
ioTag_t spektrum_bind_pin_override_ioTag;
ioTag_t spektrum_bind_plug_ioTag;
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
uint8_t rssi_channel;
uint8_t rssi_scale;
uint8_t rssi_invert;
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
uint16_t mincheck; // minimum rc end
uint16_t maxcheck; // maximum rc end
uint8_t rcInterpolation;
uint8_t rcInterpolationChannels;
uint8_t rcInterpolationInterval;
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
uint16_t rx_min_usec;
uint16_t rx_max_usec;
uint8_t max_aux_channel;
uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);
struct rxRuntimeConfig_s;
typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
typedef uint8_t (*rcFrameStatusFnPtr)(struct rxRuntimeConfig_s *rxRuntimeConfig);
@ -187,7 +152,9 @@ bool rxIsReceivingSignal(void);
bool rxAreFlightChannelsValid(void);
bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs);
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
struct rxConfig_s;
void parseRcChannels(const char *input, struct rxConfig_s *rxConfig);
#define RSSI_MAX_VALUE 1023

View File

@ -30,6 +30,7 @@
#include "common/utils.h"
#include "config/feature.h"
#include "pg/rx.h"
#include "drivers/rx/rx_spi.h"
#include "drivers/rx/rx_nrf24l01.h"

View File

@ -20,6 +20,7 @@
#pragma once
#include "pg/rx.h"
#include "rx/rx.h"
// Used in MSP. Append at end.

View File

@ -38,6 +38,8 @@
#include "telemetry/telemetry.h"
#endif
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/sbus.h"
#include "rx/sbus_channels.h"

View File

@ -28,6 +28,8 @@
#include "common/utils.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/sbus_channels.h"

View File

@ -44,6 +44,8 @@
#include "telemetry/telemetry.h"
#include "telemetry/srxl.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/spektrum.h"

View File

@ -37,6 +37,8 @@
#include "telemetry/telemetry.h"
#endif
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/sumd.h"

View File

@ -42,6 +42,8 @@
#include "telemetry/telemetry.h"
#endif
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/sumh.h"

View File

@ -36,6 +36,8 @@
#include "telemetry/telemetry.h"
#endif
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/xbus.h"

View File

@ -34,6 +34,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#ifdef BRUSHED_MOTORS_PWM_RATE

View File

@ -37,6 +37,7 @@
#include "flight/pid.h"
#include "pg/beeper_dev.h"
#include "pg/rx.h"
#include "rx/rx.h"

View File

@ -36,6 +36,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -35,6 +35,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -52,6 +52,7 @@
#include "flight/pid.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"

View File

@ -43,6 +43,7 @@
#include "flight/pid.h"
#include "pg/vcd.h"
#include "pg/rx.h"
#include "rx/rx.h"

View File

@ -37,6 +37,8 @@
#include "io/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/boardalignment.h"

View File

@ -41,6 +41,8 @@
#include "io/flashfs.h"
#include "io/beeper.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/msp.h"

View File

@ -47,6 +47,8 @@
#include "io/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/targetcustomserial.h"
#include "syslink.h"

View File

@ -36,6 +36,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -23,6 +23,7 @@
#ifdef USE_TARGET_CONFIG
#include "drivers/io.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -23,6 +23,7 @@
#ifdef USE_TARGET_CONFIG
#include "drivers/io.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -24,6 +24,7 @@
#include "platform.h"
#include "drivers/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"

View File

@ -37,6 +37,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/battery.h"

View File

@ -38,6 +38,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/acceleration.h"

View File

@ -27,6 +27,8 @@
#include "fc/config.h"
#include "pg/rx.h"
#include "rx/rx.h"
void targetConfiguration(void)

View File

@ -24,6 +24,7 @@
#include "platform.h"
#include "drivers/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"

View File

@ -48,6 +48,8 @@ const timerHardware_t timerHardware[1]; // unused
#include "fc/config.h"
#include "scheduler/scheduler.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "dyad.h"

View File

@ -35,6 +35,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -27,6 +27,8 @@
#include "io/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/barometer.h"

View File

@ -35,6 +35,8 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "io/serial.h"

View File

@ -33,6 +33,8 @@
#include "io/serial.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "sensors/battery.h"

View File

@ -201,3 +201,26 @@
#define SPI3_MOSI_PIN PB5
#endif
#endif
// Extracted from rx/rx.c and rx/rx.h
#define RX_MAPPABLE_CHANNEL_COUNT 8
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
#endif
#ifndef SERIALRX_PROVIDER
#define SERIALRX_PROVIDER 0
#endif
#define RX_MIN_USEC 885
#define RX_MAX_USEC 2115
#define RX_MID_USEC 1500
#ifndef SPEKTRUM_BIND_PIN
#define SPEKTRUM_BIND_PIN NONE
#endif
#ifndef BINDPLUG_PIN
#define BINDPLUG_PIN NONE
#endif

View File

@ -38,6 +38,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/sensor.h"

View File

@ -41,6 +41,8 @@
#include "flight/position.h"
#include "flight/imu.h"
#include "pg/rx.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "rx/jetiexbus.h"

View File

@ -66,6 +66,8 @@
#include "io/ledstrip.h"
#include "io/beeper.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "flight/mixer.h"

View File

@ -38,6 +38,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/sensor.h"

View File

@ -40,6 +40,7 @@
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/compass/compass.h"

View File

@ -48,6 +48,8 @@
#include "io/gps.h"
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/spektrum.h"
#include "io/spektrum_vtx_control.h"

View File

@ -30,6 +30,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/timer.h"
#include "drivers/serial.h"

View File

@ -190,7 +190,9 @@ rx_ranges_unittest_SRC := \
$(USER_DIR)/common/bitarray.c \
$(USER_DIR)/common/maths.c \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/rx/rx.c
$(USER_DIR)/rx/rx.c \
$(USER_DIR)/pg/pg.c \
$(USER_DIR)/pg/rx.c
rx_rx_unittest_SRC := \
@ -198,7 +200,8 @@ rx_rx_unittest_SRC := \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/common/bitarray.c \
$(USER_DIR)/common/maths.c \
$(USER_DIR)/config/feature.c
$(USER_DIR)/config/feature.c \
$(USER_DIR)/pg/rx.c
scheduler_unittest_SRC := \

View File

@ -24,6 +24,7 @@ extern "C" {
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/fc_core.h"

View File

@ -25,6 +25,7 @@ extern "C" {
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/gyro_sync.h"

View File

@ -27,9 +27,10 @@ extern "C" {
#include "platform.h"
#include "target.h"
#include "build/version.h"
#include "pg/pg.h"
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/buf_writer.h"
#include "drivers/vtx_common.h"
#include "fc/config.h"

View File

@ -21,11 +21,12 @@
#include <limits.h>
extern "C" {
#include "platform.h"
#include "build/debug.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "platform.h"
#include "pg/rx.h"
#include "common/axis.h"
#include "common/maths.h"

View File

@ -21,13 +21,16 @@
#include <cmath>
extern "C" {
#include "platform.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/compass/compass.h"

View File

@ -22,12 +22,15 @@
//#define DEBUG_LEDSTRIP
extern "C" {
#include "platform.h"
#include "build/build_config.h"
#include "common/axis.h"
#include "common/color.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "drivers/light_ws2811strip.h"

View File

@ -27,7 +27,9 @@ extern "C" {
#include "blackbox/blackbox.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "common/time.h"

View File

@ -18,6 +18,7 @@
#pragma once
#include <stdio.h>
#include <stdint.h>
#define USE_PARAMETER_GROUPS
@ -108,3 +109,5 @@ typedef struct
#define NVIC_PriorityGroup_2 0x500
#include "target.h"
#include "target/common_defaults_post.h"

View File

@ -29,6 +29,7 @@ extern "C" {
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "blackbox/blackbox.h"
#include "blackbox/blackbox_fielddefs.h"
@ -735,4 +736,4 @@ timeDelta_t getTaskDeltaTime(cfTaskId_e) { return 20000; }
}
armingDisableFlags_e getArmingDisableFlags(void) {
return (armingDisableFlags_e) 0;
}
}

View File

@ -47,6 +47,7 @@ extern "C" {
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/vcd.h"
#include "pg/rx.h"
#include "rx/rx.h"

View File

@ -28,6 +28,8 @@ extern "C" {
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "common/crc.h"
#include "common/utils.h"

View File

@ -20,6 +20,7 @@
extern "C" {
#include "platform.h"
#include "pg/pg.h"
#include "pg/rx.h"
#include "drivers/serial.h"
#include "drivers/time.h"
#include "io/serial.h"

View File

@ -25,7 +25,9 @@ extern "C" {
#include "drivers/io.h"
#include "common/maths.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "rx/rx.h"

View File

@ -23,6 +23,7 @@
extern "C" {
#include "platform.h"
#include "pg/rx.h"
#include "drivers/io.h"
#include "rx/rx.h"
#include "fc/rc_modes.h"

View File

@ -37,6 +37,7 @@ extern "C" {
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/nvic.h"
#include "drivers/serial.h"

View File

@ -36,6 +36,7 @@ extern "C" {
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/serial.h"
#include "drivers/system.h"