Adding AlienFlightNG Whoop support

Some general AlienFlight target updates
This commit is contained in:
Michael Jakob 2017-05-09 05:16:08 +02:00
parent 4cc5b9bb69
commit fe6642a7f9
8 changed files with 34 additions and 10 deletions

View File

@ -24,6 +24,8 @@
#include "common/axis.h" #include "common/axis.h"
#include "config/feature.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/pwm_esc_detect.h" #include "drivers/pwm_esc_detect.h"
@ -34,8 +36,13 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "io/serial.h"
#include "sensors/battery.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "telemetry/telemetry.h"
#include "hardware_revision.h" #include "hardware_revision.h"
#ifdef BRUSHED_MOTORS_PWM_RATE #ifdef BRUSHED_MOTORS_PWM_RATE
@ -43,6 +50,7 @@
#endif #endif
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz #define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
#define VBAT_SCALE 20
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(void) void targetConfiguration(void)
@ -78,8 +86,18 @@ void targetConfiguration(void)
pidConfigMutable()->pid_process_denom = 2; pidConfigMutable()->pid_process_denom = 2;
} }
rxConfigMutable()->spektrum_sat_bind = 5; if (!haveFrSkyRX) {
rxConfigMutable()->spektrum_sat_bind_autoreset = 1; 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) { if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;

View File

@ -29,8 +29,10 @@
#include "hardware_revision.h" #include "hardware_revision.h"
uint8_t hardwareRevision = AFF3_UNKNOWN; uint8_t hardwareRevision = AFF3_UNKNOWN;
bool haveFrSkyRX = true;
static IO_t HWDetectPin = IO_NONE; static IO_t HWDetectPin = IO_NONE;
static IO_t RXDetectPin = IO_NONE;
void detectHardwareRevision(void) void detectHardwareRevision(void)
{ {
@ -38,6 +40,10 @@ void detectHardwareRevision(void)
IOInit(HWDetectPin, OWNER_SYSTEM, 0); IOInit(HWDetectPin, OWNER_SYSTEM, 0);
IOConfigGPIO(HWDetectPin, IOCFG_IPU); IOConfigGPIO(HWDetectPin, IOCFG_IPU);
RXDetectPin = IOGetByTag(IO_TAG(BEEPER));
IOInit(RXDetectPin, OWNER_SYSTEM, 0);
IOConfigGPIO(RXDetectPin, IOCFG_IPU);
delayMicroseconds(10); // allow configuration to settle delayMicroseconds(10); // allow configuration to settle
// Check hardware revision // Check hardware revision
@ -46,6 +52,11 @@ void detectHardwareRevision(void)
} else { } else {
hardwareRevision = AFF3_REV_2; hardwareRevision = AFF3_REV_2;
} }
// Check for integrated OpenSky reciever
if (IORead(RXDetectPin)) {
haveFrSkyRX = false;
}
} }
void updateHardwareRevision(void) void updateHardwareRevision(void)

View File

@ -23,6 +23,7 @@ typedef enum awf3HardwareRevision_t {
} awf3HardwareRevision_e; } awf3HardwareRevision_e;
extern uint8_t hardwareRevision; extern uint8_t hardwareRevision;
extern bool haveFrSkyRX;
void updateHardwareRevision(void); void updateHardwareRevision(void);
void detectHardwareRevision(void); void detectHardwareRevision(void);

View File

@ -111,7 +111,6 @@
#define ADC_INSTANCE ADC2 #define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4 #define VBAT_ADC_PIN PA4
#define VBAT_SCALE_DEFAULT 20
// LED strip configuration. // LED strip configuration.
#define LED_STRIP #define LED_STRIP
@ -122,7 +121,6 @@
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP #define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define SERIALRX_UART SERIAL_PORT_USART2 #define SERIALRX_UART SERIAL_PORT_USART2
#define RX_CHANNELS_TAER #define RX_CHANNELS_TAER

View File

@ -64,7 +64,7 @@ void targetConfiguration(void)
} else { } else {
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
rxConfigMutable()->sbus_inversion = 0; 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; telemetryConfigMutable()->telemetry_inversion = 0;
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC; batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC; batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;

View File

@ -173,8 +173,6 @@
#define SERIALRX_UART SERIAL_PORT_USART2 #define SERIALRX_UART SERIAL_PORT_USART2
#define RX_CHANNELS_TAER #define RX_CHANNELS_TAER
#define TELEMETRY_UART SERIAL_PORT_USART1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTA 0xffff

View File

@ -63,7 +63,7 @@ void targetConfiguration(void)
} else { } else {
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
rxConfigMutable()->sbus_inversion = 0; 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; telemetryConfigMutable()->telemetry_inversion = 0;
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC; batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC; batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;

View File

@ -182,8 +182,6 @@
#define SERIALRX_UART SERIAL_PORT_USART2 #define SERIALRX_UART SERIAL_PORT_USART2
#define RX_CHANNELS_TAER #define RX_CHANNELS_TAER
#define TELEMETRY_UART SERIAL_PORT_USART1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTA 0xffff