mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Remove config.c's dependencies on the mw.h/board.h files. Moved some RX
code into rx_common.c. Moved some GPS code into gps_common.c. Isolated some GPS functions into gps_common.c that were called from mw.c/loop(). moved gimbal defines into gimbal.h. Moved sound & light code into statusindicator.c
This commit is contained in:
parent
8477b45061
commit
a85bfa51e3
20 changed files with 232 additions and 166 deletions
1
Makefile
1
Makefile
|
@ -80,6 +80,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
|
|||
typeconversion.c \
|
||||
serial_cli.c \
|
||||
serial_msp.c \
|
||||
statusindicator.c \
|
||||
$(CMSIS_SRC) \
|
||||
$(STDPERIPH_SRC)
|
||||
|
||||
|
|
76
src/config.c
76
src/config.c
|
@ -1,16 +1,33 @@
|
|||
#include "board.h"
|
||||
#include "flight_common.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "flight_common.h"
|
||||
|
||||
#include "drivers/system_common.h"
|
||||
|
||||
#include "statusindicator.h"
|
||||
#include "sensors_acceleration.h"
|
||||
#include "telemetry_common.h"
|
||||
#include "gps_common.h"
|
||||
|
||||
#include "config_storage.h"
|
||||
#include "config.h"
|
||||
#include "drivers/serial_common.h"
|
||||
#include "flight_mixer.h"
|
||||
#include "sensors_common.h"
|
||||
#include "boardalignment.h"
|
||||
#include "battery.h"
|
||||
#include "gimbal.h"
|
||||
#include "rx_common.h"
|
||||
#include "gps_common.h"
|
||||
|
||||
#include "runtime_config.h"
|
||||
#include "config.h"
|
||||
#include "config_storage.h"
|
||||
|
||||
void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
|
||||
|
||||
#ifndef FLASH_PAGE_COUNT
|
||||
#define FLASH_PAGE_COUNT 128
|
||||
|
@ -21,22 +38,10 @@
|
|||
|
||||
master_t mcfg; // master config struct with data independent from profiles
|
||||
config_t cfg; // profile config struct
|
||||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 62;
|
||||
static void resetConf(void);
|
||||
|
||||
void parseRcChannels(const char *input)
|
||||
{
|
||||
const char *c, *s;
|
||||
|
||||
for (c = input; *c; c++) {
|
||||
s = strchr(rcChannelLetters, *c);
|
||||
if (s)
|
||||
mcfg.rxConfig.rcmap[s - rcChannelLetters] = c - input;
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t validEEPROM(void)
|
||||
{
|
||||
const master_t *temp = (const master_t *)FLASH_WRITE_ADDR;
|
||||
|
@ -65,8 +70,6 @@ static uint8_t validEEPROM(void)
|
|||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
// Sanity check
|
||||
if (!validEEPROM())
|
||||
failureMode(10);
|
||||
|
@ -78,19 +81,8 @@ void readEEPROM(void)
|
|||
mcfg.current_profile = 0;
|
||||
memcpy(&cfg, &mcfg.profile[mcfg.current_profile], sizeof(config_t));
|
||||
|
||||
for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
|
||||
lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500;
|
||||
|
||||
for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
|
||||
int16_t tmp = 10 * i - cfg.thrMid8;
|
||||
uint8_t y = 1;
|
||||
if (tmp > 0)
|
||||
y = 100 - cfg.thrMid8;
|
||||
if (tmp < 0)
|
||||
y = cfg.thrMid8;
|
||||
lookupThrottleRC[i] = 10 * cfg.thrMid8 + tmp * (100 - cfg.thrExpo8 + (int32_t) cfg.thrExpo8 * (tmp * tmp) / (y * y)) / 10;
|
||||
lookupThrottleRC[i] = mcfg.minthrottle + (int32_t) (mcfg.maxthrottle - mcfg.minthrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
|
||||
}
|
||||
generatePitchCurve(&cfg.controlRateConfig);
|
||||
generateThrottleCurve(&cfg.controlRateConfig, mcfg.minthrottle, mcfg.maxthrottle);
|
||||
|
||||
setPIDController(cfg.pidController);
|
||||
gpsSetPIDs();
|
||||
|
@ -150,7 +142,7 @@ retry:
|
|||
// re-read written data
|
||||
readEEPROM();
|
||||
if (b)
|
||||
blinkLED(15, 20, 1);
|
||||
blinkLedAndSoundBeeper(15, 20, 1);
|
||||
}
|
||||
|
||||
void checkFirstTime(bool reset)
|
||||
|
@ -260,14 +252,14 @@ static void resetConf(void)
|
|||
cfg.P8[PIDVEL] = 120;
|
||||
cfg.I8[PIDVEL] = 45;
|
||||
cfg.D8[PIDVEL] = 1;
|
||||
cfg.rcRate8 = 90;
|
||||
cfg.rcExpo8 = 65;
|
||||
cfg.rollPitchRate = 0;
|
||||
cfg.yawRate = 0;
|
||||
cfg.controlRateConfig.rcRate8 = 90;
|
||||
cfg.controlRateConfig.rcExpo8 = 65;
|
||||
cfg.controlRateConfig.rollPitchRate = 0;
|
||||
cfg.controlRateConfig.yawRate = 0;
|
||||
cfg.dynThrPID = 0;
|
||||
cfg.tpaBreakPoint = 1500;
|
||||
cfg.thrMid8 = 50;
|
||||
cfg.thrExpo8 = 0;
|
||||
cfg.controlRateConfig.thrMid8 = 50;
|
||||
cfg.controlRateConfig.thrExpo8 = 0;
|
||||
// for (i = 0; i < CHECKBOXITEMS; i++)
|
||||
// cfg.activate[i] = 0;
|
||||
cfg.angleTrim[0] = 0;
|
||||
|
@ -283,7 +275,7 @@ static void resetConf(void)
|
|||
cfg.acc_unarmedcal = 1;
|
||||
|
||||
// Radio
|
||||
parseRcChannels("AETR1234");
|
||||
parseRcChannels("AETR1234", &mcfg.rxConfig);
|
||||
cfg.deadband = 0;
|
||||
cfg.yawdeadband = 0;
|
||||
cfg.alt_hold_throttle_neutral = 40;
|
||||
|
@ -324,7 +316,7 @@ static void resetConf(void)
|
|||
mcfg.reboot_character = 'R';
|
||||
|
||||
// custom mixer. clear by defaults.
|
||||
for (i = 0; i < MAX_MOTORS; i++)
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
|
||||
mcfg.customMixer[i].throttle = 0.0f;
|
||||
|
||||
// copy default config into all 3 profiles
|
||||
|
|
|
@ -41,3 +41,6 @@ void featureClear(uint32_t mask);
|
|||
void featureClearAll(void);
|
||||
uint32_t featureMask(void);
|
||||
|
||||
void readEEPROM(void);
|
||||
void writeEEPROM(uint8_t b, uint8_t updateProfile);
|
||||
void checkFirstTime(bool reset);
|
||||
|
|
|
@ -6,13 +6,7 @@ typedef struct config_t {
|
|||
uint8_t I8[PID_ITEM_COUNT];
|
||||
uint8_t D8[PID_ITEM_COUNT];
|
||||
|
||||
uint8_t rcRate8;
|
||||
uint8_t rcExpo8;
|
||||
uint8_t thrMid8;
|
||||
uint8_t thrExpo8;
|
||||
|
||||
uint8_t rollPitchRate;
|
||||
uint8_t yawRate;
|
||||
controlRateConfig_t controlRateConfig;
|
||||
|
||||
uint8_t dynThrPID;
|
||||
uint16_t tpaBreakPoint; // Breakpoint where TPA is activated
|
||||
|
@ -85,6 +79,7 @@ typedef struct master_t {
|
|||
uint16_t deadband3d_high; // max 3d value
|
||||
uint16_t neutral3d; // center 3d value
|
||||
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
|
||||
|
||||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
||||
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||
|
||||
|
|
|
@ -1,5 +1,33 @@
|
|||
#pragma once
|
||||
|
||||
// Syncronized with GUI. Only exception is mixer > 11, which is always returned as 11 during serialization.
|
||||
typedef enum MultiType
|
||||
{
|
||||
MULTITYPE_TRI = 1,
|
||||
MULTITYPE_QUADP = 2,
|
||||
MULTITYPE_QUADX = 3,
|
||||
MULTITYPE_BI = 4,
|
||||
MULTITYPE_GIMBAL = 5,
|
||||
MULTITYPE_Y6 = 6,
|
||||
MULTITYPE_HEX6 = 7,
|
||||
MULTITYPE_FLYING_WING = 8,
|
||||
MULTITYPE_Y4 = 9,
|
||||
MULTITYPE_HEX6X = 10,
|
||||
MULTITYPE_OCTOX8 = 11, // Java GUI is same for the next 3 configs
|
||||
MULTITYPE_OCTOFLATP = 12, // MultiWinGui shows this differently
|
||||
MULTITYPE_OCTOFLATX = 13, // MultiWinGui shows this differently
|
||||
MULTITYPE_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported)
|
||||
MULTITYPE_HELI_120_CCPM = 15,
|
||||
MULTITYPE_HELI_90_DEG = 16,
|
||||
MULTITYPE_VTAIL4 = 17,
|
||||
MULTITYPE_HEX6H = 18,
|
||||
MULTITYPE_PPM_TO_SERVO = 19, // PPM -> servo relay
|
||||
MULTITYPE_DUALCOPTER = 20,
|
||||
MULTITYPE_SINGLECOPTER = 21,
|
||||
MULTITYPE_CUSTOM = 22, // no current GUI displays this
|
||||
MULTITYPE_LAST = 23
|
||||
} MultiType;
|
||||
|
||||
// Custom mixer data per motor
|
||||
typedef struct motorMixer_t {
|
||||
float throttle;
|
||||
|
|
7
src/gimbal.h
Normal file
7
src/gimbal.h
Normal file
|
@ -0,0 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
typedef enum GimbalFlags {
|
||||
GIMBAL_NORMAL = 1 << 0,
|
||||
GIMBAL_MIXTILT = 1 << 1,
|
||||
GIMBAL_FORWARDAUX = 1 << 2,
|
||||
} GimbalFlags;
|
|
@ -243,7 +243,8 @@ static void GPS_calc_nav_rate(int max_speed);
|
|||
static void GPS_update_crosstrack(void);
|
||||
static bool UBLOX_parse_gps(void);
|
||||
static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow);
|
||||
int32_t wrap_18000(int32_t error);
|
||||
|
||||
static int32_t wrap_18000(int32_t error);
|
||||
static int32_t wrap_36000(int32_t angle);
|
||||
|
||||
typedef struct {
|
||||
|
@ -785,7 +786,7 @@ static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow)
|
|||
////////////////////////////////////////////////////////////////////////////////////
|
||||
// Utilities
|
||||
//
|
||||
int32_t wrap_18000(int32_t error)
|
||||
static int32_t wrap_18000(int32_t error)
|
||||
{
|
||||
if (error > 18000)
|
||||
error -= 36000;
|
||||
|
@ -1265,3 +1266,18 @@ static bool UBLOX_parse_gps(void)
|
|||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void updateGpsState(void)
|
||||
{
|
||||
float sin_yaw_y = sinf(heading * 0.0174532925f);
|
||||
float cos_yaw_x = cosf(heading * 0.0174532925f);
|
||||
if (cfg.nav_slew_rate) {
|
||||
nav_rated[LON] += constrain(wrap_18000(nav[LON] - nav_rated[LON]), -cfg.nav_slew_rate, cfg.nav_slew_rate); // TODO check this on uint8
|
||||
nav_rated[LAT] += constrain(wrap_18000(nav[LAT] - nav_rated[LAT]), -cfg.nav_slew_rate, cfg.nav_slew_rate);
|
||||
GPS_angle[ROLL] = (nav_rated[LON] * cos_yaw_x - nav_rated[LAT] * sin_yaw_y) / 10;
|
||||
GPS_angle[PITCH] = (nav_rated[LON] * sin_yaw_y + nav_rated[LAT] * cos_yaw_x) / 10;
|
||||
} else {
|
||||
GPS_angle[ROLL] = (nav[LON] * cos_yaw_x - nav[LAT] * sin_yaw_y) / 10;
|
||||
GPS_angle[PITCH] = (nav[LON] * sin_yaw_y + nav[LAT] * cos_yaw_x) / 10;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,5 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#define LAT 0
|
||||
#define LON 1
|
||||
|
||||
typedef enum {
|
||||
GPS_NMEA = 0,
|
||||
GPS_UBLOX,
|
||||
|
@ -17,3 +20,13 @@ typedef enum {
|
|||
GPS_BAUD_9600,
|
||||
GPS_BAUD_MAX = GPS_BAUD_9600
|
||||
} GPSBaudRates;
|
||||
|
||||
// gps
|
||||
void gpsInit(uint8_t baudrate);
|
||||
void gpsThread(void);
|
||||
int8_t gpsSetPassthrough(void);
|
||||
void GPS_reset_home_position(void);
|
||||
void GPS_reset_nav(void);
|
||||
void GPS_set_next_wp(int32_t* lat, int32_t* lon);
|
||||
void gpsSetPIDs(void);
|
||||
void updateGpsState(void);
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
#include "flight_common.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include "gps_common.h"
|
||||
#include "rx_sbus.h"
|
||||
#include "rx_sumd.h"
|
||||
#include "rx_spektrum.h"
|
||||
|
|
43
src/mw.c
43
src/mw.c
|
@ -7,11 +7,13 @@
|
|||
#include "serial_cli.h"
|
||||
#include "telemetry_common.h"
|
||||
#include "typeconversion.h"
|
||||
#include "gps_common.h"
|
||||
#include "rx_common.h"
|
||||
#include "rx_sbus.h"
|
||||
#include "rx_sumd.h"
|
||||
#include "rx_spektrum.h"
|
||||
#include "failsafe.h"
|
||||
#include "statusindicator.h"
|
||||
|
||||
// June 2013 V2.2-dev
|
||||
|
||||
|
@ -24,8 +26,6 @@ int16_t headFreeModeHold;
|
|||
int16_t telemTemperature1; // gyro sensor temperature
|
||||
|
||||
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
|
||||
int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
uint16_t rssi; // range: [0;1023]
|
||||
|
||||
static void pidMultiWii(void);
|
||||
|
@ -65,21 +65,6 @@ bool AccInflightCalibrationSavetoEEProm = false;
|
|||
bool AccInflightCalibrationActive = false;
|
||||
uint16_t InflightcalibratingA = 0;
|
||||
|
||||
void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||
{
|
||||
uint8_t i, r;
|
||||
|
||||
for (r = 0; r < repeat; r++) {
|
||||
for (i = 0; i < num; i++) {
|
||||
LED0_TOGGLE; // switch LEDPIN state
|
||||
BEEP_ON;
|
||||
delay(wait);
|
||||
BEEP_OFF;
|
||||
}
|
||||
delay(60);
|
||||
}
|
||||
}
|
||||
|
||||
void annexCode(void)
|
||||
{
|
||||
static uint32_t calibratedAccTime;
|
||||
|
@ -114,7 +99,7 @@ void annexCode(void)
|
|||
|
||||
tmp2 = tmp / 100;
|
||||
rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 100) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 100;
|
||||
prop1 = 100 - (uint16_t)cfg.rollPitchRate * tmp / 500;
|
||||
prop1 = 100 - (uint16_t)cfg.controlRateConfig.rollPitchRate * tmp / 500;
|
||||
prop1 = (uint16_t)prop1 * prop2 / 100;
|
||||
} else { // YAW
|
||||
if (cfg.yawdeadband) {
|
||||
|
@ -125,7 +110,7 @@ void annexCode(void)
|
|||
}
|
||||
}
|
||||
rcCommand[axis] = tmp * -mcfg.yaw_control_direction;
|
||||
prop1 = 100 - (uint16_t)cfg.yawRate * abs(tmp) / 500;
|
||||
prop1 = 100 - (uint16_t)cfg.controlRateConfig.yawRate * abs(tmp) / 500;
|
||||
}
|
||||
dynP8[axis] = (uint16_t)cfg.P8[axis] * prop1 / 100;
|
||||
dynI8[axis] = (uint16_t)cfg.I8[axis] * prop1 / 100;
|
||||
|
@ -222,7 +207,7 @@ static void mwArm(void)
|
|||
headFreeModeHold = heading;
|
||||
}
|
||||
} else if (!f.ARMED) {
|
||||
blinkLED(2, 255, 1);
|
||||
blinkLedAndSoundBeeper(2, 255, 1);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -311,10 +296,10 @@ static void pidRewrite(void)
|
|||
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int)mcfg.max_angle_inclination), +mcfg.max_angle_inclination) - angle[axis] + cfg.angleTrim[axis]; // 16 bits is ok here
|
||||
}
|
||||
if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
||||
AngleRateTmp = (((int32_t)(cfg.yawRate + 27) * rcCommand[2]) >> 5);
|
||||
AngleRateTmp = (((int32_t)(cfg.controlRateConfig.yawRate + 27) * rcCommand[2]) >> 5);
|
||||
} else {
|
||||
if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
||||
AngleRateTmp = ((int32_t) (cfg.rollPitchRate + 27) * rcCommand[axis]) >> 4;
|
||||
AngleRateTmp = ((int32_t) (cfg.controlRateConfig.rollPitchRate + 27) * rcCommand[axis]) >> 4;
|
||||
if (f.HORIZON_MODE) {
|
||||
// mix up angle error to desired AngleRateTmp to add a little auto-level feel
|
||||
AngleRateTmp += (errorAngle * cfg.I8[PIDLEVEL]) >> 8;
|
||||
|
@ -507,7 +492,7 @@ void loop(void)
|
|||
if (i) {
|
||||
mcfg.current_profile = i - 1;
|
||||
writeEEPROM(0, false);
|
||||
blinkLED(2, 40, i);
|
||||
blinkLedAndSoundBeeper(2, 40, i);
|
||||
// TODO alarmArray[0] = i;
|
||||
}
|
||||
|
||||
|
@ -816,17 +801,7 @@ void loop(void)
|
|||
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
if ((f.GPS_HOME_MODE || f.GPS_HOLD_MODE) && f.GPS_FIX_HOME) {
|
||||
float sin_yaw_y = sinf(heading * 0.0174532925f);
|
||||
float cos_yaw_x = cosf(heading * 0.0174532925f);
|
||||
if (cfg.nav_slew_rate) {
|
||||
nav_rated[LON] += constrain(wrap_18000(nav[LON] - nav_rated[LON]), -cfg.nav_slew_rate, cfg.nav_slew_rate); // TODO check this on uint8
|
||||
nav_rated[LAT] += constrain(wrap_18000(nav[LAT] - nav_rated[LAT]), -cfg.nav_slew_rate, cfg.nav_slew_rate);
|
||||
GPS_angle[ROLL] = (nav_rated[LON] * cos_yaw_x - nav_rated[LAT] * sin_yaw_y) / 10;
|
||||
GPS_angle[PITCH] = (nav_rated[LON] * sin_yaw_y + nav_rated[LAT] * cos_yaw_x) / 10;
|
||||
} else {
|
||||
GPS_angle[ROLL] = (nav[LON] * cos_yaw_x - nav[LAT] * sin_yaw_y) / 10;
|
||||
GPS_angle[PITCH] = (nav[LON] * sin_yaw_y + nav[LAT] * cos_yaw_x) / 10;
|
||||
}
|
||||
updateGpsState();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
61
src/mw.h
61
src/mw.h
|
@ -9,9 +9,6 @@
|
|||
|
||||
#define VERSION 230
|
||||
|
||||
#define LAT 0
|
||||
#define LON 1
|
||||
|
||||
// Serial GPS only variables
|
||||
// navigation mode
|
||||
typedef enum NavigationMode
|
||||
|
@ -21,40 +18,7 @@ typedef enum NavigationMode
|
|||
NAV_MODE_WP
|
||||
} NavigationMode;
|
||||
|
||||
// Syncronized with GUI. Only exception is mixer > 11, which is always returned as 11 during serialization.
|
||||
typedef enum MultiType
|
||||
{
|
||||
MULTITYPE_TRI = 1,
|
||||
MULTITYPE_QUADP = 2,
|
||||
MULTITYPE_QUADX = 3,
|
||||
MULTITYPE_BI = 4,
|
||||
MULTITYPE_GIMBAL = 5,
|
||||
MULTITYPE_Y6 = 6,
|
||||
MULTITYPE_HEX6 = 7,
|
||||
MULTITYPE_FLYING_WING = 8,
|
||||
MULTITYPE_Y4 = 9,
|
||||
MULTITYPE_HEX6X = 10,
|
||||
MULTITYPE_OCTOX8 = 11, // Java GUI is same for the next 3 configs
|
||||
MULTITYPE_OCTOFLATP = 12, // MultiWinGui shows this differently
|
||||
MULTITYPE_OCTOFLATX = 13, // MultiWinGui shows this differently
|
||||
MULTITYPE_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported)
|
||||
MULTITYPE_HELI_120_CCPM = 15,
|
||||
MULTITYPE_HELI_90_DEG = 16,
|
||||
MULTITYPE_VTAIL4 = 17,
|
||||
MULTITYPE_HEX6H = 18,
|
||||
MULTITYPE_PPM_TO_SERVO = 19, // PPM -> servo relay
|
||||
MULTITYPE_DUALCOPTER = 20,
|
||||
MULTITYPE_SINGLECOPTER = 21,
|
||||
MULTITYPE_CUSTOM = 22, // no current GUI displays this
|
||||
MULTITYPE_LAST = 23
|
||||
} MultiType;
|
||||
|
||||
typedef enum GimbalFlags {
|
||||
GIMBAL_NORMAL = 1 << 0,
|
||||
GIMBAL_MIXTILT = 1 << 1,
|
||||
GIMBAL_FORWARDAUX = 1 << 2,
|
||||
} GimbalFlags;
|
||||
|
||||
#include "gimbal.h"
|
||||
#include "flight_mixer.h"
|
||||
|
||||
enum {
|
||||
|
@ -105,11 +69,6 @@ extern uint8_t vbat;
|
|||
extern int16_t telemTemperature1; // gyro sensor temperature
|
||||
extern uint8_t toggleBeep;
|
||||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
|
||||
// GPS stuff
|
||||
extern int32_t GPS_coord[2];
|
||||
extern int32_t GPS_home[2];
|
||||
|
@ -143,7 +102,6 @@ void loop(void);
|
|||
void imuInit(void);
|
||||
void annexCode(void);
|
||||
void computeIMU(void);
|
||||
void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat);
|
||||
int getEstimatedAltitude(void);
|
||||
|
||||
// Sensors
|
||||
|
@ -169,26 +127,9 @@ void mixTable(void);
|
|||
void serialInit(uint32_t baudrate);
|
||||
void serialCom(void);
|
||||
|
||||
// Config
|
||||
void parseRcChannels(const char *input);
|
||||
void readEEPROM(void);
|
||||
void writeEEPROM(uint8_t b, uint8_t updateProfile);
|
||||
void checkFirstTime(bool reset);
|
||||
|
||||
// buzzer
|
||||
void buzzer(bool warn_vbat);
|
||||
void systemBeep(bool onoff);
|
||||
|
||||
// cli
|
||||
void cliProcess(void);
|
||||
|
||||
// gps
|
||||
void gpsInit(uint8_t baudrate);
|
||||
void gpsThread(void);
|
||||
void gpsSetPIDs(void);
|
||||
int8_t gpsSetPassthrough(void);
|
||||
void GPS_reset_home_position(void);
|
||||
void GPS_reset_nav(void);
|
||||
void GPS_set_next_wp(int32_t* lat, int32_t* lon);
|
||||
int32_t wrap_18000(int32_t error);
|
||||
|
||||
|
|
|
@ -2,6 +2,8 @@
|
|||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "rx_common.h"
|
||||
|
@ -9,7 +11,10 @@
|
|||
|
||||
#include "drivers/pwm_common.h"
|
||||
|
||||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
int16_t rcData[RC_CHANS]; // interval [1000;2000]
|
||||
|
||||
rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
|
||||
|
@ -52,3 +57,39 @@ void computeRC(rxConfig_t *rxConfig)
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
void generatePitchCurve(controlRateConfig_t *controlRateConfig)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
|
||||
lookupPitchRollRC[i] = (2500 + controlRateConfig->rcExpo8 * (i * i - 25)) * i * (int32_t) controlRateConfig->rcRate8 / 2500;
|
||||
}
|
||||
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, uint16_t minThrottle, uint16_t maxThrottle)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
|
||||
int16_t tmp = 10 * i - controlRateConfig->thrMid8;
|
||||
uint8_t y = 1;
|
||||
if (tmp > 0)
|
||||
y = 100 - controlRateConfig->thrMid8;
|
||||
if (tmp < 0)
|
||||
y = controlRateConfig->thrMid8;
|
||||
lookupThrottleRC[i] = 10 * controlRateConfig->thrMid8 + tmp * (100 - controlRateConfig->thrExpo8 + (int32_t) controlRateConfig->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
|
||||
lookupThrottleRC[i] = minThrottle + (int32_t) (maxThrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
|
||||
}
|
||||
}
|
||||
|
||||
void parseRcChannels(const char *input, rxConfig_t *rxConfig)
|
||||
{
|
||||
const char *c, *s;
|
||||
|
||||
for (c = input; *c; c++) {
|
||||
s = strchr(rcChannelLetters, *c);
|
||||
if (s)
|
||||
rxConfig->rcmap[s - rcChannelLetters] = c - input;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -43,8 +43,27 @@ typedef struct rxConfig_s {
|
|||
uint16_t maxcheck; // maximum rc end
|
||||
} rxConfig_t;
|
||||
|
||||
typedef struct controlRateConfig_s {
|
||||
uint8_t rcRate8;
|
||||
uint8_t rcExpo8;
|
||||
uint8_t thrMid8;
|
||||
uint8_t thrExpo8;
|
||||
uint8_t rollPitchRate;
|
||||
uint8_t yawRate;
|
||||
} controlRateConfig_t;
|
||||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
|
||||
extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
|
||||
typedef uint16_t (* rcReadRawDataPtr)(rxConfig_t *rxConfig, uint8_t chan); // used by receiver driver to return channel data
|
||||
|
||||
uint16_t pwmReadRawRC(rxConfig_t *rxConfig, uint8_t chan);
|
||||
void computeRC(rxConfig_t *rxConfig);
|
||||
|
||||
void generatePitchCurve(controlRateConfig_t *controlRateConfig);
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, uint16_t minThrottle, uint16_t maxThrottle);
|
||||
|
||||
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
|
||||
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#include "common/maths.h"
|
||||
|
||||
#include "flight_common.h"
|
||||
|
||||
#include "statusindicator.h"
|
||||
|
||||
void GYRO_Common(void)
|
||||
{
|
||||
|
@ -37,7 +37,7 @@ void GYRO_Common(void)
|
|||
continue;
|
||||
}
|
||||
gyroZero[axis] = (g[axis] + (CALIBRATING_GYRO_CYCLES / 2)) / CALIBRATING_GYRO_CYCLES;
|
||||
blinkLED(10, 15, 1);
|
||||
blinkLedAndSoundBeeper(10, 15, 1);
|
||||
}
|
||||
}
|
||||
calibratingG--;
|
||||
|
|
|
@ -171,12 +171,12 @@ const clivalue_t valueTable[] = {
|
|||
{ "alt_hold_fast_change", VAR_UINT8, &cfg.alt_hold_fast_change, 0, 1 },
|
||||
{ "throttle_correction_value", VAR_UINT8, &cfg.throttle_correction_value, 0, 150 },
|
||||
{ "throttle_correction_angle", VAR_UINT16, &cfg.throttle_correction_angle, 1, 900 },
|
||||
{ "rc_rate", VAR_UINT8, &cfg.rcRate8, 0, 250 },
|
||||
{ "rc_expo", VAR_UINT8, &cfg.rcExpo8, 0, 100 },
|
||||
{ "thr_mid", VAR_UINT8, &cfg.thrMid8, 0, 100 },
|
||||
{ "thr_expo", VAR_UINT8, &cfg.thrExpo8, 0, 100 },
|
||||
{ "roll_pitch_rate", VAR_UINT8, &cfg.rollPitchRate, 0, 100 },
|
||||
{ "yawrate", VAR_UINT8, &cfg.yawRate, 0, 100 },
|
||||
{ "rc_rate", VAR_UINT8, &cfg.controlRateConfig.rcRate8, 0, 250 },
|
||||
{ "rc_expo", VAR_UINT8, &cfg.controlRateConfig.rcExpo8, 0, 100 },
|
||||
{ "thr_mid", VAR_UINT8, &cfg.controlRateConfig.thrMid8, 0, 100 },
|
||||
{ "thr_expo", VAR_UINT8, &cfg.controlRateConfig.thrExpo8, 0, 100 },
|
||||
{ "roll_pitch_rate", VAR_UINT8, &cfg.controlRateConfig.rollPitchRate, 0, 100 },
|
||||
{ "yawrate", VAR_UINT8, &cfg.controlRateConfig.yawRate, 0, 100 },
|
||||
{ "tparate", VAR_UINT8, &cfg.dynThrPID, 0, 100},
|
||||
{ "tpa_breakpoint", VAR_UINT16, &cfg.tpaBreakPoint, 1000, 2000},
|
||||
{ "failsafe_delay", VAR_UINT8, &cfg.failsafe_delay, 0, 200 },
|
||||
|
@ -731,7 +731,7 @@ static void cliMap(char *cmdline)
|
|||
cliPrint("Must be any order of AETR1234\r\n");
|
||||
return;
|
||||
}
|
||||
parseRcChannels(cmdline);
|
||||
parseRcChannels(cmdline, &mcfg.rxConfig);
|
||||
}
|
||||
cliPrint("Current assignment: ");
|
||||
for (i = 0; i < 8; i++)
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include "gps_common.h"
|
||||
#include "serial_cli.h"
|
||||
#include "telemetry_common.h"
|
||||
#include "flight_common.h"
|
||||
|
@ -318,13 +319,13 @@ static void evaluateCommand(void)
|
|||
headSerialReply(0);
|
||||
break;
|
||||
case MSP_SET_RC_TUNING:
|
||||
cfg.rcRate8 = read8();
|
||||
cfg.rcExpo8 = read8();
|
||||
cfg.rollPitchRate = read8();
|
||||
cfg.yawRate = read8();
|
||||
cfg.controlRateConfig.rcRate8 = read8();
|
||||
cfg.controlRateConfig.rcExpo8 = read8();
|
||||
cfg.controlRateConfig.rollPitchRate = read8();
|
||||
cfg.controlRateConfig.yawRate = read8();
|
||||
cfg.dynThrPID = read8();
|
||||
cfg.thrMid8 = read8();
|
||||
cfg.thrExpo8 = read8();
|
||||
cfg.controlRateConfig.thrMid8 = read8();
|
||||
cfg.controlRateConfig.thrExpo8 = read8();
|
||||
headSerialReply(0);
|
||||
break;
|
||||
case MSP_SET_MISC:
|
||||
|
@ -479,13 +480,13 @@ static void evaluateCommand(void)
|
|||
break;
|
||||
case MSP_RC_TUNING:
|
||||
headSerialReply(7);
|
||||
serialize8(cfg.rcRate8);
|
||||
serialize8(cfg.rcExpo8);
|
||||
serialize8(cfg.rollPitchRate);
|
||||
serialize8(cfg.yawRate);
|
||||
serialize8(cfg.controlRateConfig.rcRate8);
|
||||
serialize8(cfg.controlRateConfig.rcExpo8);
|
||||
serialize8(cfg.controlRateConfig.rollPitchRate);
|
||||
serialize8(cfg.controlRateConfig.yawRate);
|
||||
serialize8(cfg.dynThrPID);
|
||||
serialize8(cfg.thrMid8);
|
||||
serialize8(cfg.thrExpo8);
|
||||
serialize8(cfg.controlRateConfig.thrMid8);
|
||||
serialize8(cfg.controlRateConfig.thrExpo8);
|
||||
break;
|
||||
case MSP_PID:
|
||||
headSerialReply(3 * PID_ITEM_COUNT);
|
||||
|
|
27
src/statusindicator.c
Normal file
27
src/statusindicator.c
Normal file
|
@ -0,0 +1,27 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/system_common.h"
|
||||
#include "drivers/gpio_common.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "statusindicator.h"
|
||||
|
||||
void blinkLedAndSoundBeeper(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||
{
|
||||
uint8_t i, r;
|
||||
|
||||
for (r = 0; r < repeat; r++) {
|
||||
for (i = 0; i < num; i++) {
|
||||
LED0_TOGGLE; // switch LEDPIN state
|
||||
BEEP_ON;
|
||||
delay(wait);
|
||||
BEEP_OFF;
|
||||
}
|
||||
delay(60);
|
||||
}
|
||||
}
|
3
src/statusindicator.h
Normal file
3
src/statusindicator.h
Normal file
|
@ -0,0 +1,3 @@
|
|||
#pragma once
|
||||
|
||||
void blinkLedAndSoundBeeper(uint8_t num, uint8_t wait, uint8_t repeat);
|
|
@ -6,6 +6,8 @@
|
|||
|
||||
#include "flight_common.h"
|
||||
|
||||
#include "gps_common.h"
|
||||
|
||||
#include "telemetry_common.h"
|
||||
#include "telemetry_frsky.h"
|
||||
|
||||
|
|
|
@ -44,6 +44,7 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include "gps_common.h"
|
||||
#include "telemetry_hott.h"
|
||||
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue