1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Split escAndServoConfig into motor and servo parts

This commit is contained in:
Martin Budden 2016-09-26 09:31:28 +01:00
parent 60da2b52ff
commit a11d0bdb4d
35 changed files with 173 additions and 118 deletions

View file

@ -52,7 +52,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/display.h" #include "io/display.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/gps.h" #include "io/gps.h"
@ -530,7 +531,7 @@ static void writeIntraframe(void)
* Write the throttle separately from the rest of the RC data so we can apply a predictor to it. * Write the throttle separately from the rest of the RC data so we can apply a predictor to it.
* Throttle lies in range [minthrottle..maxthrottle]: * Throttle lies in range [minthrottle..maxthrottle]:
*/ */
blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - masterConfig.escAndServoConfig.minthrottle); blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - masterConfig.motorConfig.minthrottle);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
/* /*
@ -574,7 +575,7 @@ static void writeIntraframe(void)
blackboxWriteSigned16VBArray(blackboxCurrent->debug, 4); blackboxWriteSigned16VBArray(blackboxCurrent->debug, 4);
//Motors can be below minthrottle when disarmed, but that doesn't happen much //Motors can be below minthrottle when disarmed, but that doesn't happen much
blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - masterConfig.escAndServoConfig.minthrottle); blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - masterConfig.motorConfig.minthrottle);
//Motors tend to be similar to each other so use the first motor's value as a predictor of the others //Motors tend to be similar to each other so use the first motor's value as a predictor of the others
for (x = 1; x < motorCount; x++) { for (x = 1; x < motorCount; x++) {
@ -931,7 +932,7 @@ void stopInTestMode(void)
*/ */
bool inMotorTestMode(void) { bool inMotorTestMode(void) {
static uint32_t resetTime = 0; static uint32_t resetTime = 0;
uint16_t inactiveMotorCommand = (feature(FEATURE_3D) ? masterConfig.flight3DConfig.neutral3d : masterConfig.escAndServoConfig.mincommand); uint16_t inactiveMotorCommand = (feature(FEATURE_3D) ? masterConfig.flight3DConfig.neutral3d : masterConfig.motorConfig.mincommand);
int i; int i;
bool atLeastOneMotorActivated = false; bool atLeastOneMotorActivated = false;
@ -1198,8 +1199,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime); BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name); BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.motorConfig.minthrottle);
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle); BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.motorConfig.maxthrottle);
BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale)); BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
BLACKBOX_PRINT_HEADER_LINE("acc_1G:%u", acc.acc_1G); BLACKBOX_PRINT_HEADER_LINE("acc_1G:%u", acc.acc_1G);

View file

@ -32,7 +32,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/display.h" #include "io/display.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/osd.h" #include "io/osd.h"

View file

@ -52,7 +52,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
@ -235,19 +236,25 @@ void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
sensorAlignmentConfig->mag_align = ALIGN_DEFAULT; sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
} }
void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig) void resetMotorConfig(motorConfig_t *motorConfig)
{ {
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
escAndServoConfig->minthrottle = 1000; motorConfig->minthrottle = 1000;
#else #else
escAndServoConfig->minthrottle = 1070; motorConfig->minthrottle = 1070;
#endif #endif
escAndServoConfig->maxthrottle = 2000; motorConfig->maxthrottle = 2000;
escAndServoConfig->mincommand = 1000; motorConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500; motorConfig->maxEscThrottleJumpMs = 0;
escAndServoConfig->maxEscThrottleJumpMs = 0;
} }
#ifdef USE_SERVOS
void resetServoConfig(servoConfig_t *servoConfig)
{
servoConfig->servoCenterPulse = 1500;
}
#endif
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig) void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
{ {
flight3DConfig->deadband3d_low = 1406; flight3DConfig->deadband3d_low = 1406;
@ -368,7 +375,7 @@ controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
uint16_t getCurrentMinthrottle(void) uint16_t getCurrentMinthrottle(void)
{ {
return masterConfig.escAndServoConfig.minthrottle; return masterConfig.motorConfig.minthrottle;
} }
// Default settings // Default settings
@ -485,7 +492,10 @@ void createDefaultConfig(master_t *config)
config->airplaneConfig.fixedwing_althold_dir = 1; config->airplaneConfig.fixedwing_althold_dir = 1;
// Motor/ESC/Servo // Motor/ESC/Servo
resetEscAndServoConfig(&config->escAndServoConfig); resetMotorConfig(&config->motorConfig);
#ifdef USE_SERVOS
resetServoConfig(&config->servoConfig);
#endif
resetFlight3DConfig(&config->flight3DConfig); resetFlight3DConfig(&config->flight3DConfig);
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
@ -639,7 +649,7 @@ static void resetConf(void)
void activateControlRateConfig(void) void activateControlRateConfig(void)
{ {
generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig); generateThrottleCurve(currentControlRateProfile, &masterConfig.motorConfig);
} }
void activateConfig(void) void activateConfig(void)
@ -652,7 +662,7 @@ void activateConfig(void)
useRcControlsConfig( useRcControlsConfig(
masterConfig.modeActivationConditions, masterConfig.modeActivationConditions,
&masterConfig.escAndServoConfig, &masterConfig.motorConfig,
&currentProfile->pidProfile &currentProfile->pidProfile
); );
@ -674,7 +684,7 @@ void activateConfig(void)
mixerUseConfigs( mixerUseConfigs(
&masterConfig.flight3DConfig, &masterConfig.flight3DConfig,
&masterConfig.escAndServoConfig, &masterConfig.motorConfig,
&masterConfig.mixerConfig, &masterConfig.mixerConfig,
&masterConfig.airplaneConfig, &masterConfig.airplaneConfig,
&masterConfig.rxConfig &masterConfig.rxConfig
@ -700,7 +710,7 @@ void activateConfig(void)
&currentProfile->pidProfile, &currentProfile->pidProfile,
&masterConfig.barometerConfig, &masterConfig.barometerConfig,
&masterConfig.rcControlsConfig, &masterConfig.rcControlsConfig,
&masterConfig.escAndServoConfig &masterConfig.motorConfig
); );
#ifdef BARO #ifdef BARO

View file

@ -45,7 +45,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -28,7 +28,8 @@ typedef struct master_s {
// motor/esc/servo related stuff // motor/esc/servo related stuff
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS]; motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
escAndServoConfig_t escAndServoConfig; motorConfig_t motorConfig;
servoConfig_t servoConfig;
flight3DConfig_t flight3DConfig; flight3DConfig_t flight3DConfig;
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)

View file

@ -45,7 +45,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -53,7 +53,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/display.h" #include "io/display.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/gimbal.h" #include "io/gimbal.h"

View file

@ -47,7 +47,7 @@
#include "io/gps.h" #include "io/gps.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/escservo.h" #include "io/motors.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/vtx.h" #include "io/vtx.h"
@ -62,7 +62,7 @@
#include "fc/mw.h" #include "fc/mw.h"
static escAndServoConfig_t *escAndServoConfig; static motorConfig_t *motorConfig;
static pidProfile_t *pidProfile; static pidProfile_t *pidProfile;
// true if arming is done via the sticks (as opposed to a switch) // true if arming is done via the sticks (as opposed to a switch)
@ -516,7 +516,7 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
case ADJUSTMENT_THROTTLE_EXPO: case ADJUSTMENT_THROTTLE_EXPO:
newValue = constrain((int)controlRateConfig->thrExpo8 + delta, 0, 100); // FIXME magic numbers repeated in serial_cli.c newValue = constrain((int)controlRateConfig->thrExpo8 + delta, 0, 100); // FIXME magic numbers repeated in serial_cli.c
controlRateConfig->thrExpo8 = newValue; controlRateConfig->thrExpo8 = newValue;
generateThrottleCurve(controlRateConfig, escAndServoConfig); generateThrottleCurve(controlRateConfig, motorConfig);
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_THROTTLE_EXPO, newValue); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_THROTTLE_EXPO, newValue);
break; break;
case ADJUSTMENT_PITCH_ROLL_RATE: case ADJUSTMENT_PITCH_ROLL_RATE:
@ -709,9 +709,9 @@ int32_t getRcStickDeflection(int32_t axis, uint16_t midrc) {
return MIN(ABS(rcData[axis] - midrc), 500); return MIN(ABS(rcData[axis] - midrc), 500);
} }
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse) void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, motorConfig_t *motorConfig, pidProfile_t *pidProfileToUse)
{ {
escAndServoConfig = escAndServoConfigToUse; motorConfig = motorConfig;
pidProfile = pidProfileToUse; pidProfile = pidProfileToUse;
isUsingSticksToArm = !isModeActivationConditionPresent(modeActivationConditions, BOXARM); isUsingSticksToArm = !isModeActivationConditionPresent(modeActivationConditions, BOXARM);

View file

@ -263,5 +263,5 @@ bool isUsingSticksForArming(void);
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc); int32_t getRcStickDeflection(int32_t axis, uint16_t midrc);
bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationConditions, boxId_e modeId); bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationConditions, boxId_e modeId);
struct pidProfile_s; struct pidProfile_s;
struct escAndServoConfig_s; struct motorConfig_s;
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, struct escAndServoConfig_s *escAndServoConfigToUse, struct pidProfile_s *pidProfileToUse); void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, struct motorConfig_s *motorConfigToUse, struct pidProfile_s *pidProfileToUse);

View file

@ -23,7 +23,7 @@
#include "config/config.h" #include "config/config.h"
#include "config/feature.h" #include "config/feature.h"
#include "io/escservo.h" #include "io/motors.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -34,10 +34,10 @@
#define THROTTLE_LOOKUP_LENGTH 12 #define THROTTLE_LOOKUP_LENGTH 12
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig) void generateThrottleCurve(controlRateConfig_t *controlRateConfig, motorConfig_t *motorConfig)
{ {
uint8_t i; uint8_t i;
uint16_t minThrottle = (feature(FEATURE_3D && IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) ? PWM_RANGE_MIN : escAndServoConfig->minthrottle); uint16_t minThrottle = (feature(FEATURE_3D && IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH)) ? PWM_RANGE_MIN : motorConfig->minthrottle);
for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) { for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
int16_t tmp = 10 * i - controlRateConfig->thrMid8; int16_t tmp = 10 * i - controlRateConfig->thrMid8;
@ -47,7 +47,7 @@ void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoCo
if (tmp < 0) if (tmp < 0)
y = controlRateConfig->thrMid8; y = controlRateConfig->thrMid8;
lookupThrottleRC[i] = 10 * controlRateConfig->thrMid8 + tmp * (100 - controlRateConfig->thrExpo8 + (int32_t) controlRateConfig->thrExpo8 * (tmp * tmp) / (y * y)) / 10; lookupThrottleRC[i] = 10 * controlRateConfig->thrMid8 + tmp * (100 - controlRateConfig->thrExpo8 + (int32_t) controlRateConfig->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
lookupThrottleRC[i] = minThrottle + (int32_t) (escAndServoConfig->maxthrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] lookupThrottleRC[i] = minThrottle + (int32_t) (motorConfig->maxthrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
} }
} }

View file

@ -18,8 +18,8 @@
#pragma once #pragma once
struct controlRateConfig_s; struct controlRateConfig_s;
struct escAndServoConfig_s; struct motorConfig_s;
void generateThrottleCurve(struct controlRateConfig_s *controlRateConfig, struct escAndServoConfig_s *escAndServoConfig); void generateThrottleCurve(struct controlRateConfig_s *controlRateConfig, struct motorConfig_s *motorConfig);
int16_t rcLookupThrottle(int32_t tmp); int16_t rcLookupThrottle(int32_t tmp);

View file

@ -40,7 +40,7 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/escservo.h" #include "io/motors.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
@ -60,19 +60,19 @@ int32_t vario = 0; // variometer in cm/s
static barometerConfig_t *barometerConfig; static barometerConfig_t *barometerConfig;
static pidProfile_t *pidProfile; static pidProfile_t *pidProfile;
static rcControlsConfig_t *rcControlsConfig; static rcControlsConfig_t *rcControlsConfig;
static escAndServoConfig_t *escAndServoConfig; static motorConfig_t *motorConfig;
void configureAltitudeHold( void configureAltitudeHold(
pidProfile_t *initialPidProfile, pidProfile_t *initialPidProfile,
barometerConfig_t *intialBarometerConfig, barometerConfig_t *intialBarometerConfig,
rcControlsConfig_t *initialRcControlsConfig, rcControlsConfig_t *initialRcControlsConfig,
escAndServoConfig_t *initialEscAndServoConfig motorConfig_t *initialMotorConfig
) )
{ {
pidProfile = initialPidProfile; pidProfile = initialPidProfile;
barometerConfig = intialBarometerConfig; barometerConfig = intialBarometerConfig;
rcControlsConfig = initialRcControlsConfig; rcControlsConfig = initialRcControlsConfig;
escAndServoConfig = initialEscAndServoConfig; motorConfig = initialMotorConfig;
} }
#if defined(BARO) || defined(SONAR) #if defined(BARO) || defined(SONAR)
@ -100,7 +100,7 @@ static void applyMultirotorAltHold(void)
AltHold = EstAlt; AltHold = EstAlt;
isAltHoldChanged = 0; isAltHoldChanged = 0;
} }
rcCommand[THROTTLE] = constrain(initialThrottleHold + altHoldThrottleAdjustment, escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle); rcCommand[THROTTLE] = constrain(initialThrottleHold + altHoldThrottleAdjustment, motorConfig->minthrottle, motorConfig->maxthrottle);
} }
} else { } else {
// slow alt changes, mostly used for aerial photography // slow alt changes, mostly used for aerial photography
@ -114,7 +114,7 @@ static void applyMultirotorAltHold(void)
velocityControl = 0; velocityControl = 0;
isAltHoldChanged = 0; isAltHoldChanged = 0;
} }
rcCommand[THROTTLE] = constrain(initialThrottleHold + altHoldThrottleAdjustment, escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle); rcCommand[THROTTLE] = constrain(initialThrottleHold + altHoldThrottleAdjustment, motorConfig->minthrottle, motorConfig->maxthrottle);
} }
} }

View file

@ -25,10 +25,10 @@ void calculateEstimatedAltitude(uint32_t currentTime);
struct pidProfile_s; struct pidProfile_s;
struct barometerConfig_s; struct barometerConfig_s;
struct rcControlsConfig_s; struct rcControlsConfig_s;
struct escAndServoConfig_s; struct motorConfig_s;
void configureAltitudeHold(struct pidProfile_s *initialPidProfile, struct barometerConfig_s *intialBarometerConfig, struct rcControlsConfig_s *initialRcControlsConfig, struct escAndServoConfig_s *initialEscAndServoConfig); void configureAltitudeHold(struct pidProfile_s *initialPidProfile, struct barometerConfig_s *intialBarometerConfig, struct rcControlsConfig_s *initialRcControlsConfig, struct motorConfig_s *initialMotorConfig);
struct airplaneConfig_t; struct airplaneConfig_s;
void applyAltHold(struct airplaneConfig_s *airplaneConfig); void applyAltHold(struct airplaneConfig_s *airplaneConfig);
void updateAltHoldState(void); void updateAltHoldState(void);
void updateSonarAltHoldState(void); void updateSonarAltHoldState(void);

View file

@ -27,7 +27,7 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/escservo.h" #include "io/motors.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"

View file

@ -40,7 +40,8 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
@ -64,7 +65,7 @@ int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
static mixerConfig_t *mixerConfig; static mixerConfig_t *mixerConfig;
static flight3DConfig_t *flight3DConfig; static flight3DConfig_t *flight3DConfig;
static escAndServoConfig_t *escAndServoConfig; static motorConfig_t *motorConfig;
static airplaneConfig_t *airplaneConfig; static airplaneConfig_t *airplaneConfig;
static rxConfig_t *rxConfig; static rxConfig_t *rxConfig;
static bool syncPwmWithPidLoop = false; static bool syncPwmWithPidLoop = false;
@ -337,13 +338,13 @@ static motorMixer_t *customMixers;
void mixerUseConfigs( void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse, flight3DConfig_t *flight3DConfigToUse,
escAndServoConfig_t *escAndServoConfigToUse, motorConfig_t *motorConfigToUse,
mixerConfig_t *mixerConfigToUse, mixerConfig_t *mixerConfigToUse,
airplaneConfig_t *airplaneConfigToUse, airplaneConfig_t *airplaneConfigToUse,
rxConfig_t *rxConfigToUse) rxConfig_t *rxConfigToUse)
{ {
flight3DConfig = flight3DConfigToUse; flight3DConfig = flight3DConfigToUse;
escAndServoConfig = escAndServoConfigToUse; motorConfig = motorConfigToUse;
mixerConfig = mixerConfigToUse; mixerConfig = mixerConfigToUse;
airplaneConfig = airplaneConfigToUse; airplaneConfig = airplaneConfigToUse;
rxConfig = rxConfigToUse; rxConfig = rxConfigToUse;
@ -548,7 +549,7 @@ void mixerResetDisarmedMotors(void)
int i; int i;
// set disarmed motor values // set disarmed motor values
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig->neutral3d : escAndServoConfig->mincommand; motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig->neutral3d : motorConfig->mincommand;
} }
#ifdef USE_SERVOS #ifdef USE_SERVOS
@ -659,7 +660,7 @@ void writeAllMotors(int16_t mc)
void stopMotors(void) void stopMotors(void)
{ {
writeAllMotors(feature(FEATURE_3D) ? flight3DConfig->neutral3d : escAndServoConfig->mincommand); writeAllMotors(feature(FEATURE_3D) ? flight3DConfig->neutral3d : motorConfig->mincommand);
delay(50); // give the timers and ESCs a chance to react. delay(50); // give the timers and ESCs a chance to react.
} }
@ -798,25 +799,25 @@ void mixTable(void *pidProfilePtr)
if ((rcCommand[THROTTLE] <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling if ((rcCommand[THROTTLE] <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling
throttleMax = flight3DConfig->deadband3d_low; throttleMax = flight3DConfig->deadband3d_low;
throttleMin = escAndServoConfig->minthrottle; throttleMin = motorConfig->minthrottle;
throttlePrevious = rcCommand[THROTTLE]; throttlePrevious = rcCommand[THROTTLE];
throttle = rcCommand[THROTTLE] + flight3DConfig->deadband3d_throttle; throttle = rcCommand[THROTTLE] + flight3DConfig->deadband3d_throttle;
} else if (rcCommand[THROTTLE] >= (rxConfig->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling } else if (rcCommand[THROTTLE] >= (rxConfig->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling
throttleMax = escAndServoConfig->maxthrottle; throttleMax = motorConfig->maxthrottle;
throttleMin = flight3DConfig->deadband3d_high; throttleMin = flight3DConfig->deadband3d_high;
throttlePrevious = rcCommand[THROTTLE]; throttlePrevious = rcCommand[THROTTLE];
throttle = rcCommand[THROTTLE] - flight3DConfig->deadband3d_throttle; throttle = rcCommand[THROTTLE] - flight3DConfig->deadband3d_throttle;
} else if ((throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive } else if ((throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive
throttle = throttleMax = flight3DConfig->deadband3d_low; throttle = throttleMax = flight3DConfig->deadband3d_low;
throttleMin = escAndServoConfig->minthrottle; throttleMin = motorConfig->minthrottle;
} else { // Deadband handling from positive to negative } else { // Deadband handling from positive to negative
throttleMax = escAndServoConfig->maxthrottle; throttleMax = motorConfig->maxthrottle;
throttle = throttleMin = flight3DConfig->deadband3d_high; throttle = throttleMin = flight3DConfig->deadband3d_high;
} }
} else { } else {
throttle = rcCommand[THROTTLE]; throttle = rcCommand[THROTTLE];
throttleMin = escAndServoConfig->minthrottle; throttleMin = motorConfig->minthrottle;
throttleMax = escAndServoConfig->maxthrottle; throttleMax = motorConfig->maxthrottle;
} }
throttleRange = throttleMax - throttleMin; throttleRange = throttleMax - throttleMin;
@ -840,34 +841,34 @@ void mixTable(void *pidProfilePtr)
motor[i] = rollPitchYawMix[i] + constrain(throttle * currentMixer[i].throttle, throttleMin, throttleMax); motor[i] = rollPitchYawMix[i] + constrain(throttle * currentMixer[i].throttle, throttleMin, throttleMax);
if (isFailsafeActive) { if (isFailsafeActive) {
motor[i] = constrain(motor[i], escAndServoConfig->mincommand, escAndServoConfig->maxthrottle); motor[i] = constrain(motor[i], motorConfig->mincommand, motorConfig->maxthrottle);
} else if (feature(FEATURE_3D)) { } else if (feature(FEATURE_3D)) {
if (throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle)) { if (throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle)) {
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, flight3DConfig->deadband3d_low); motor[i] = constrain(motor[i], motorConfig->minthrottle, flight3DConfig->deadband3d_low);
} else { } else {
motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, escAndServoConfig->maxthrottle); motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, motorConfig->maxthrottle);
} }
} else { } else {
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle); motor[i] = constrain(motor[i], motorConfig->minthrottle, motorConfig->maxthrottle);
} }
// Motor stop handling // Motor stop handling
if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) { if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) {
if (((rcData[THROTTLE]) < rxConfig->mincheck)) { if (((rcData[THROTTLE]) < rxConfig->mincheck)) {
motor[i] = escAndServoConfig->mincommand; motor[i] = motorConfig->mincommand;
} }
} }
} }
// Anti Desync feature for ESC's. Limit rapid throttle changes // Anti Desync feature for ESC's. Limit rapid throttle changes
if (escAndServoConfig->maxEscThrottleJumpMs) { if (motorConfig->maxEscThrottleJumpMs) {
const int16_t maxThrottleStep = constrain(escAndServoConfig->maxEscThrottleJumpMs / (1000 / targetPidLooptime), 2, 10000); const int16_t maxThrottleStep = constrain(motorConfig->maxEscThrottleJumpMs / (1000 / targetPidLooptime), 2, 10000);
// Only makes sense when it's within the range // Only makes sense when it's within the range
if (maxThrottleStep < throttleRange) { if (maxThrottleStep < throttleRange) {
static int16_t motorPrevious[MAX_SUPPORTED_MOTORS]; static int16_t motorPrevious[MAX_SUPPORTED_MOTORS];
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, motorPrevious[i] + maxThrottleStep); // Only limit accelerating situation motor[i] = constrain(motor[i], motorConfig->minthrottle, motorPrevious[i] + maxThrottleStep); // Only limit accelerating situation
motorPrevious[i] = motor[i]; motorPrevious[i] = motor[i];
} }
} }

View file

@ -178,7 +178,7 @@ typedef struct servoParam_s {
} __attribute__ ((__packed__)) servoParam_t; } __attribute__ ((__packed__)) servoParam_t;
struct gimbalConfig_s; struct gimbalConfig_s;
struct escAndServoConfig_s; struct motorConfig_s;
struct rxConfig_s; struct rxConfig_s;
extern int16_t servo[MAX_SUPPORTED_SERVOS]; extern int16_t servo[MAX_SUPPORTED_SERVOS];
@ -189,12 +189,12 @@ void filterServos(void);
extern int16_t motor[MAX_SUPPORTED_MOTORS]; extern int16_t motor[MAX_SUPPORTED_MOTORS];
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
struct escAndServoConfig_s; struct motorConfig_s;
struct rxConfig_s; struct rxConfig_s;
void mixerUseConfigs( void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse, flight3DConfig_t *flight3DConfigToUse,
struct escAndServoConfig_s *escAndServoConfigToUse, struct motorConfig_s *motorConfigToUse,
mixerConfig_t *mixerConfigToUse, mixerConfig_t *mixerConfigToUse,
airplaneConfig_t *airplaneConfigToUse, airplaneConfig_t *airplaneConfigToUse,
struct rxConfig_s *rxConfigToUse); struct rxConfig_s *rxConfigToUse);

View file

@ -52,7 +52,7 @@ void GPS_reset_home_position(void);
void GPS_reset_nav(void); void GPS_reset_nav(void);
void GPS_set_next_wp(int32_t* lat, int32_t* lon); void GPS_set_next_wp(int32_t* lat, int32_t* lon);
void gpsUseProfile(gpsProfile_t *gpsProfileToUse); void gpsUseProfile(gpsProfile_t *gpsProfileToUse);
void gpsUsePIDs(pidProfile_t *pidProfile); void gpsUsePIDs(struct pidProfile_s *pidProfile);
void updateGpsStateForHomeAndHoldMode(void); void updateGpsStateForHomeAndHoldMode(void);
void updateGpsWaypointsAndMode(void); void updateGpsWaypointsAndMode(void);

View file

@ -55,7 +55,8 @@
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gps.h" #include "io/gps.h"

View file

@ -17,12 +17,11 @@
#pragma once #pragma once
typedef struct escAndServoConfig_s { typedef struct motorConfig_s {
// PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms) // PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms)
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed. uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
uint16_t maxEscThrottleJumpMs; uint16_t maxEscThrottleJumpMs;
} escAndServoConfig_t; } motorConfig_t;

View file

@ -74,7 +74,8 @@
#include "io/serial.h" #include "io/serial.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -51,7 +51,8 @@
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -670,11 +671,13 @@ const clivalue_t valueTable[] = {
{ "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } }, { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } }, { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "max_esc_throttle_jump", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.maxEscThrottleJumpMs, .config.minmax = { 0, 1000 } },
{ "max_esc_throttle_jump", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxEscThrottleJumpMs, .config.minmax = { 0, 1000 } }, #ifdef USE_SERVOS
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
#endif
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently, { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently,

View file

@ -51,7 +51,8 @@
#include "rx/msp.h" #include "rx/msp.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/gimbal.h" #include "io/gimbal.h"
@ -110,7 +111,7 @@ extern uint16_t cycleTime; // FIXME dependency on mw.c
extern uint16_t rssi; // FIXME dependency on mw.c extern uint16_t rssi; // FIXME dependency on mw.c
extern void resetProfile(profile_t *profile); extern void resetProfile(profile_t *profile);
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse); void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, motorConfig_t *motorConfigToUse, pidProfile_t *pidProfileToUse);
const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller. const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
@ -926,9 +927,9 @@ static bool processOutCommand(uint8_t cmdMSP)
headSerialReply(2 * 5 + 3 + 3 + 2 + 4); headSerialReply(2 * 5 + 3 + 3 + 2 + 4);
serialize16(masterConfig.rxConfig.midrc); serialize16(masterConfig.rxConfig.midrc);
serialize16(masterConfig.escAndServoConfig.minthrottle); serialize16(masterConfig.motorConfig.minthrottle);
serialize16(masterConfig.escAndServoConfig.maxthrottle); serialize16(masterConfig.motorConfig.maxthrottle);
serialize16(masterConfig.escAndServoConfig.mincommand); serialize16(masterConfig.motorConfig.mincommand);
serialize16(masterConfig.failsafeConfig.failsafe_throttle); serialize16(masterConfig.failsafeConfig.failsafe_throttle);
@ -1425,7 +1426,7 @@ static bool processInCommand(void)
mac->range.startStep = read8(); mac->range.startStep = read8();
mac->range.endStep = read8(); mac->range.endStep = read8();
useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.escAndServoConfig, &currentProfile->pidProfile); useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.motorConfig, &currentProfile->pidProfile);
} else { } else {
headSerialError(0); headSerialError(0);
} }
@ -1481,9 +1482,9 @@ static bool processInCommand(void)
if (tmp < 1600 && tmp > 1400) if (tmp < 1600 && tmp > 1400)
masterConfig.rxConfig.midrc = tmp; masterConfig.rxConfig.midrc = tmp;
masterConfig.escAndServoConfig.minthrottle = read16(); masterConfig.motorConfig.minthrottle = read16();
masterConfig.escAndServoConfig.maxthrottle = read16(); masterConfig.motorConfig.maxthrottle = read16();
masterConfig.escAndServoConfig.mincommand = read16(); masterConfig.motorConfig.mincommand = read16();
masterConfig.failsafeConfig.failsafe_throttle = read16(); masterConfig.failsafeConfig.failsafe_throttle = read16();

23
src/main/io/servos.h Normal file
View file

@ -0,0 +1,23 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef struct servoConfig_s {
// PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms)
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
} servoConfig_t;

View file

@ -49,7 +49,7 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -69,7 +69,8 @@
#include "io/serial.h" #include "io/serial.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
@ -289,7 +290,7 @@ void init(void)
#ifdef USE_SERVOS #ifdef USE_SERVOS
pwm_params.useServos = isMixerUsingServos(); pwm_params.useServos = isMixerUsingServos();
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING); pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
pwm_params.servoCenterPulse = masterConfig.escAndServoConfig.servoCenterPulse; pwm_params.servoCenterPulse = masterConfig.servoConfig.servoCenterPulse;
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate; pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
#endif #endif
@ -299,7 +300,7 @@ void init(void)
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED);
pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol; pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol;
pwm_params.motorPwmRate = use_unsyncedPwm ? masterConfig.motor_pwm_rate : 0; pwm_params.motorPwmRate = use_unsyncedPwm ? masterConfig.motor_pwm_rate : 0;
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; pwm_params.idlePulse = masterConfig.motorConfig.mincommand;
if (feature(FEATURE_3D)) if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;

View file

@ -47,7 +47,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -50,7 +50,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -50,7 +50,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -50,7 +50,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -53,7 +53,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
@ -84,8 +85,8 @@ void targetConfiguration(master_t *config)
config->mixerMode = MIXER_HEX6X; config->mixerMode = MIXER_HEX6X;
config->rxConfig.serialrx_provider = 2; config->rxConfig.serialrx_provider = 2;
config->escAndServoConfig.minthrottle = 1070; config->motorConfig.minthrottle = 1070;
config->escAndServoConfig.maxthrottle = 2000; config->motorConfig.maxthrottle = 2000;
config->boardAlignment.pitchDegrees = 10; config->boardAlignment.pitchDegrees = 10;
//config->rcControlsConfig.deadband = 10; //config->rcControlsConfig.deadband = 10;

View file

@ -50,7 +50,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
@ -78,8 +79,8 @@
// alternative defaults settings for COLIBRI RACE targets // alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(master_t *config) { void targetConfiguration(master_t *config) {
config->escAndServoConfig.minthrottle = 1025; config->motorConfig.minthrottle = 1025;
config->escAndServoConfig.maxthrottle = 1980; config->motorConfig.maxthrottle = 1980;
config->batteryConfig.vbatmaxcellvoltage = 45; config->batteryConfig.vbatmaxcellvoltage = 45;
config->batteryConfig.vbatmincellvoltage = 30; config->batteryConfig.vbatmincellvoltage = 30;
} }

View file

@ -31,7 +31,8 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/msp.h" #include "rx/msp.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/gimbal.h" #include "io/gimbal.h"
@ -72,7 +73,7 @@
#include "bus_bst.h" #include "bus_bst.h"
#include "i2c_bst.h" #include "i2c_bst.h"
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse); void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, motorConfig_t *motorConfigToUse, pidProfile_t *pidProfileToUse);
#define BST_PROTOCOL_VERSION 0 #define BST_PROTOCOL_VERSION 0
@ -749,9 +750,9 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
case BST_MISC: case BST_MISC:
bstWrite16(masterConfig.rxConfig.midrc); bstWrite16(masterConfig.rxConfig.midrc);
bstWrite16(masterConfig.escAndServoConfig.minthrottle); bstWrite16(masterConfig.motorConfig.minthrottle);
bstWrite16(masterConfig.escAndServoConfig.maxthrottle); bstWrite16(masterConfig.motorConfig.maxthrottle);
bstWrite16(masterConfig.escAndServoConfig.mincommand); bstWrite16(masterConfig.motorConfig.mincommand);
bstWrite16(masterConfig.failsafeConfig.failsafe_throttle); bstWrite16(masterConfig.failsafeConfig.failsafe_throttle);
@ -1062,7 +1063,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
mac->range.startStep = bstRead8(); mac->range.startStep = bstRead8();
mac->range.endStep = bstRead8(); mac->range.endStep = bstRead8();
useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.escAndServoConfig, &currentProfile->pidProfile); useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.motorConfig, &currentProfile->pidProfile);
} else { } else {
ret = BST_FAILED; ret = BST_FAILED;
} }
@ -1114,9 +1115,9 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
if (tmp < 1600 && tmp > 1400) if (tmp < 1600 && tmp > 1400)
masterConfig.rxConfig.midrc = tmp; masterConfig.rxConfig.midrc = tmp;
masterConfig.escAndServoConfig.minthrottle = bstRead16(); masterConfig.motorConfig.minthrottle = bstRead16();
masterConfig.escAndServoConfig.maxthrottle = bstRead16(); masterConfig.motorConfig.maxthrottle = bstRead16();
masterConfig.escAndServoConfig.mincommand = bstRead16(); masterConfig.motorConfig.mincommand = bstRead16();
masterConfig.failsafeConfig.failsafe_throttle = bstRead16(); masterConfig.failsafeConfig.failsafe_throttle = bstRead16();

View file

@ -50,7 +50,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"

View file

@ -54,7 +54,8 @@
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/escservo.h" #include "io/motors.h"
#include "io/servos.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h" #include "io/osd.h"

View file

@ -31,7 +31,7 @@
#include "rx/msp.h" #include "rx/msp.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/escservo.h" #include "io/motors.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/gimbal.h" #include "io/gimbal.h"