Merge pull request #3150 from AlienWiiBF/AFF3_whoop
Adding AlienFlightNG Whoop support
This commit is contained in:
commit
9b03b52004
|
@ -24,6 +24,8 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
|
||||
|
@ -34,8 +36,13 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
|
@ -43,6 +50,7 @@
|
|||
#endif
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||
#define VBAT_SCALE 20
|
||||
|
||||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
|
@ -78,8 +86,18 @@ void targetConfiguration(void)
|
|||
pidConfigMutable()->pid_process_denom = 2;
|
||||
}
|
||||
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
if (!haveFrSkyRX) {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048;
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;
|
||||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->sbus_inversion = 0;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
featureSet(FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
|
|
|
@ -29,8 +29,10 @@
|
|||
#include "hardware_revision.h"
|
||||
|
||||
uint8_t hardwareRevision = AFF3_UNKNOWN;
|
||||
bool haveFrSkyRX = true;
|
||||
|
||||
static IO_t HWDetectPin = IO_NONE;
|
||||
static IO_t RXDetectPin = IO_NONE;
|
||||
|
||||
void detectHardwareRevision(void)
|
||||
{
|
||||
|
@ -38,6 +40,10 @@ void detectHardwareRevision(void)
|
|||
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||
|
||||
RXDetectPin = IOGetByTag(IO_TAG(BEEPER));
|
||||
IOInit(RXDetectPin, OWNER_SYSTEM, 0);
|
||||
IOConfigGPIO(RXDetectPin, IOCFG_IPU);
|
||||
|
||||
delayMicroseconds(10); // allow configuration to settle
|
||||
|
||||
// Check hardware revision
|
||||
|
@ -46,6 +52,11 @@ void detectHardwareRevision(void)
|
|||
} else {
|
||||
hardwareRevision = AFF3_REV_2;
|
||||
}
|
||||
|
||||
// Check for integrated OpenSky reciever
|
||||
if (IORead(RXDetectPin)) {
|
||||
haveFrSkyRX = false;
|
||||
}
|
||||
}
|
||||
|
||||
void updateHardwareRevision(void)
|
||||
|
|
|
@ -23,6 +23,7 @@ typedef enum awf3HardwareRevision_t {
|
|||
} awf3HardwareRevision_e;
|
||||
|
||||
extern uint8_t hardwareRevision;
|
||||
extern bool haveFrSkyRX;
|
||||
|
||||
void updateHardwareRevision(void);
|
||||
void detectHardwareRevision(void);
|
||||
|
|
|
@ -111,7 +111,6 @@
|
|||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define VBAT_SCALE_DEFAULT 20
|
||||
|
||||
// LED strip configuration.
|
||||
#define LED_STRIP
|
||||
|
@ -122,7 +121,6 @@
|
|||
|
||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
|
|
|
@ -64,7 +64,7 @@ void targetConfiguration(void)
|
|||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->sbus_inversion = 0;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
||||
|
|
|
@ -173,8 +173,6 @@
|
|||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define TELEMETRY_UART SERIAL_PORT_USART1
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
|
|
|
@ -63,7 +63,7 @@ void targetConfiguration(void)
|
|||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->sbus_inversion = 0;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
||||
|
|
|
@ -182,8 +182,6 @@
|
|||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define TELEMETRY_UART SERIAL_PORT_USART1
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
|
|
Loading…
Reference in New Issue