diff --git a/Makefile b/Makefile
index 2681e36d2e..f6c21ffab2 100644
--- a/Makefile
+++ b/Makefile
@@ -524,7 +524,6 @@ COMMON_SRC = \
fc/rc_curves.c \
fc/serial_cli.c \
io/beeper.c \
- io/motors.c \
io/serial.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c
index e431547d79..b3822b06c7 100644
--- a/src/main/blackbox/blackbox.c
+++ b/src/main/blackbox/blackbox.c
@@ -57,8 +57,6 @@
#include "fc/runtime_config.h"
#include "io/beeper.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/gimbal.h"
#include "io/gps.h"
#include "io/ledstrip.h"
diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c
index 5611c3a27b..9169136bf0 100644
--- a/src/main/blackbox/blackbox_io.c
+++ b/src/main/blackbox/blackbox_io.c
@@ -52,8 +52,6 @@
#include "sensors/battery.h"
#include "io/beeper.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "fc/rc_controls.h"
#include "io/gimbal.h"
diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h
index adb64d7e32..f363dcaa14 100644
--- a/src/main/config/config_master.h
+++ b/src/main/config/config_master.h
@@ -45,12 +45,9 @@
#include "io/osd.h"
#include "io/ledstrip.h"
#include "io/serial.h"
-#include "io/servos.h"
#include "telemetry/telemetry.h"
-#define servoConfig(x) (&masterConfig.servoConfig)
-#define servoConfigMutable(x) (&masterConfig.servoConfig)
#define servoMixerConfig(x) (&masterConfig.servoMixerConfig)
#define servoMixerConfigMutable(x) (&masterConfig.servoMixerConfig)
#define imuConfig(x) (&masterConfig.imuConfig)
@@ -94,7 +91,6 @@ typedef struct master_s {
#endif
#ifdef USE_SERVOS
- servoConfig_t servoConfig;
servoMixerConfig_t servoMixerConfig;
servoMixer_t customServoMixer[MAX_SERVO_RULES];
#endif
diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h
index f1de0e2552..ed91f230cc 100644
--- a/src/main/config/parameter_group_ids.h
+++ b/src/main/config/parameter_group_ids.h
@@ -62,6 +62,15 @@
#define PG_RX_CHANNEL_RANGE_CONFIG 44
//#define PG_MODE_COLOR_CONFIG 45
//#define PG_SPECIAL_COLOR_CONFIG 46
+//#define PG_PILOT_CONFIG 47
+//#define PG_MSP_SERVER_CONFIG 48
+//#define PG_VOLTAGE_METER_CONFIG 49
+//#define PG_AMPERAGE_METER_CONFIG 50
+//#define PG_DEBUG_CONFIG 51
+#define PG_SERVO_CONFIG 52
+//#define PG_IBUS_TELEMETRY_CONFIG 53
+//#define PG_VTX_CONFIG 54
+
// Driver configuration
//#define PG_DRIVER_PWM_RX_CONFIG 100
diff --git a/src/main/fc/config.c b/src/main/fc/config.c
index 1dca743b44..259db0e58d 100755
--- a/src/main/fc/config.c
+++ b/src/main/fc/config.c
@@ -45,7 +45,6 @@
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
-#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
@@ -228,14 +227,6 @@ void validateNavConfig(navConfig_t * navConfig)
}
#endif
-#ifdef USE_SERVOS
-void resetServoConfig(servoConfig_t *servoConfig)
-{
- servoConfig->servoCenterPulse = 1500;
- servoConfig->servoPwmRate = 50;
-}
-#endif
-
#ifdef TELEMETRY
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
{
@@ -411,7 +402,6 @@ void createDefaultConfig(master_t *config)
#ifdef USE_SERVOS
resetServoMixerConfig(&config->servoMixerConfig);
- resetServoConfig(&config->servoConfig);
#endif
#ifdef GPS
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index 63ced128ce..d6e13153ac 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -77,8 +77,6 @@
#include "io/serial.h"
#include "io/flashfs.h"
#include "io/gps.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/gimbal.h"
#include "io/ledstrip.h"
#include "io/dashboard.h"
@@ -118,6 +116,9 @@
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
+#include "config/parameter_group.h"
+#include "config/parameter_group_ids.h"
+
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 09e540c964..441dee7d2b 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -66,10 +66,8 @@
#include "io/gps.h"
#include "io/gimbal.h"
#include "io/ledstrip.h"
-#include "io/motors.h"
#include "io/serial.h"
#include "io/serial_4way.h"
-#include "io/servos.h"
#include "msp/msp.h"
#include "msp/msp_protocol.h"
diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c
index f4f164c5eb..b41d3ae4a9 100755
--- a/src/main/fc/fc_tasks.c
+++ b/src/main/fc/fc_tasks.c
@@ -48,8 +48,6 @@
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/osd.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/pwmdriver_i2c.h"
#include "io/serial.h"
diff --git a/src/main/fc/mw.c b/src/main/fc/mw.c
index 001c3f0338..66c1efde40 100755
--- a/src/main/fc/mw.c
+++ b/src/main/fc/mw.c
@@ -53,11 +53,8 @@
#include "io/beeper.h"
#include "io/dashboard.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/gimbal.h"
#include "io/gps.h"
-#include "io/motors.h"
#include "io/serial.h"
#include "io/statusindicator.h"
#include "io/asyncfatfs/asyncfatfs.h"
diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c
index 658925ecdd..24f0ce3631 100644
--- a/src/main/fc/rc_controls.c
+++ b/src/main/fc/rc_controls.c
@@ -45,7 +45,6 @@
#include "io/gps.h"
#include "io/beeper.h"
-#include "io/motors.h"
#include "rx/rx.h"
diff --git a/src/main/fc/rc_curves.c b/src/main/fc/rc_curves.c
index 382b7ac73e..af37568e6f 100644
--- a/src/main/fc/rc_curves.c
+++ b/src/main/fc/rc_curves.c
@@ -23,7 +23,8 @@
#include "rx/rx.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
-#include "io/motors.h"
+
+#include "flight/mixer.h"
#define PITCH_LOOKUP_LENGTH 7
diff --git a/src/main/fc/serial_cli.c b/src/main/fc/serial_cli.c
index 1cb024d886..2c56db1db5 100644
--- a/src/main/fc/serial_cli.c
+++ b/src/main/fc/serial_cli.c
@@ -83,10 +83,8 @@ uint8_t cliMode = 0;
#include "io/gimbal.h"
#include "io/gps.h"
#include "io/ledstrip.h"
-#include "io/motors.h"
#include "io/osd.h"
#include "io/serial.h"
-#include "io/servos.h"
#include "rx/rx.h"
#include "rx/spektrum.h"
@@ -618,6 +616,11 @@ static const clivalue_t valueTable[] = {
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, neutral3d) },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_throttle) },
+#ifdef USE_SERVOS
+// PG_SERVO_CONFIG
+ { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_SERVO_CONFIG, offsetof(servoConfig_t, servoCenterPulse) },
+ { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 50, 498 }, PG_SERVO_CONFIG, offsetof(servoConfig_t, servoPwmRate) },
+#endif
};
#else
@@ -773,8 +776,6 @@ const clivalue_t valueTable[] = {
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
{ "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &servoMixerConfig()->servo_lowpass_freq, .config.minmax = { 10, 400} },
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
- { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
- { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoPwmRate, .config.minmax = { 50, 498 } },
{ "fw_iterm_throw_limit", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.fixedWingItermThrowLimit, .config.minmax = { FW_ITERM_THROW_LIMIT_MIN, FW_ITERM_THROW_LIMIT_MAX} },
#endif
@@ -1098,6 +1099,7 @@ static rxChannelRangeConfig_t rxChannelRangeConfigsCopy[NON_AUX_CHANNEL_COUNT];
static motorConfig_t motorConfigCopy;
static boardAlignment_t boardAlignmentCopy;
#ifdef USE_SERVOS
+static servoConfig_t servoConfigCopy;
static gimbalConfig_t gimbalConfigCopy;
#endif
static motorMixer_t customMotorMixerCopy[MAX_SUPPORTED_MOTORS];
@@ -1128,6 +1130,7 @@ static void backupConfigs(void)
motorConfigCopy = *motorConfig();
boardAlignmentCopy = *boardAlignment();
#ifdef USE_SERVOS
+ servoConfigCopy = *servoConfig();
gimbalConfigCopy = *gimbalConfig();
#endif
for (int ii = 0; ii < MAX_SUPPORTED_MOTORS; ++ii) {
@@ -1160,6 +1163,7 @@ static void restoreConfigs(void)
*motorConfigMutable() = motorConfigCopy;
*boardAlignmentMutable() = boardAlignmentCopy;
#ifdef USE_SERVOS
+ *servoConfigMutable() = servoConfigCopy;
*gimbalConfigMutable() = gimbalConfigCopy;
#endif
for (int ii = 0; ii < MAX_SUPPORTED_MOTORS; ++ii) {
@@ -1210,11 +1214,12 @@ static void dumpValues(uint16_t valueSection, uint8_t dumpMask, const master_t *
dumpPgValues(MASTER_VALUE, dumpMask, PG_RX_CONFIG, &rxConfigCopy, rxConfig());
dumpPgValues(MASTER_VALUE, dumpMask, PG_MOTOR_CONFIG, &motorConfigCopy, motorConfig());
dumpPgValues(MASTER_VALUE, dumpMask, PG_BOARD_ALIGNMENT, &boardAlignmentCopy, boardAlignment());
-#ifdef USE_SERVOS
- dumpPgValues(MASTER_VALUE, dumpMask, PG_GIMBAL_CONFIG, &gimbalConfigCopy, gimbalConfig());
-#endif
dumpPgValues(MASTER_VALUE, dumpMask, PG_MIXER_CONFIG, &mixerConfigCopy, mixerConfig());
dumpPgValues(MASTER_VALUE, dumpMask, PG_MOTOR_3D_CONFIG, &flight3DConfigCopy, flight3DConfig());
+#ifdef USE_SERVOS
+ dumpPgValues(MASTER_VALUE, dumpMask, PG_SERVO_CONFIG, &servoConfigCopy, servoConfig());
+ dumpPgValues(MASTER_VALUE, dumpMask, PG_GIMBAL_CONFIG, &gimbalConfigCopy, gimbalConfig());
+#endif
return;
}
#endif
diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c
index 7754af12c7..4d59a04c0a 100644
--- a/src/main/flight/failsafe.c
+++ b/src/main/flight/failsafe.c
@@ -32,7 +32,6 @@
#include "drivers/system.h"
#include "io/beeper.h"
-#include "io/motors.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c
index 14bd81226e..347940b2d2 100755
--- a/src/main/flight/mixer.c
+++ b/src/main/flight/mixer.c
@@ -37,9 +37,6 @@
#include "rx/rx.h"
-#include "io/gimbal.h"
-#include "io/motors.h"
-
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
@@ -86,6 +83,26 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
.yaw_jump_prevention_limit = 200
);
+#ifdef BRUSHED_MOTORS
+#define DEFAULT_PWM_PROTOCOL PWM_TYPE_BRUSHED
+#define DEFAULT_PWM_RATE 16000
+#define DEFAULT_MIN_THROTTLE 1000
+#else
+#define DEFAULT_PWM_PROTOCOL PWM_TYPE_STANDARD
+#define DEFAULT_PWM_RATE 400
+#define DEFAULT_MIN_THROTTLE 1150
+#endif
+
+PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 1);
+
+PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
+ .minthrottle = DEFAULT_MIN_THROTTLE,
+ .motorPwmProtocol = DEFAULT_PWM_PROTOCOL,
+ .motorPwmRate = DEFAULT_PWM_RATE,
+ .maxthrottle = 1850,
+ .mincommand = 1000
+);
+
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
PG_REGISTER_ARR(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer, PG_MOTOR_MIXER, 0);
diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h
index 0166f79c23..bf7822c283 100644
--- a/src/main/flight/mixer.h
+++ b/src/main/flight/mixer.h
@@ -108,6 +108,17 @@ typedef struct flight3DConfig_s {
PG_DECLARE(flight3DConfig_t, flight3DConfig);
+typedef struct motorConfig_s {
+ // PWM values, in milliseconds, common range is 1000-2000 (1ms 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 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 motorPwmRate; // The update rate of motor outputs (50-498Hz)
+ uint8_t motorPwmProtocol;
+} motorConfig_t;
+
+PG_DECLARE(motorConfig_t, motorConfig);
+
#define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF
extern int16_t motor[MAX_SUPPORTED_MOTORS];
diff --git a/src/main/flight/navigation_rewrite.h b/src/main/flight/navigation_rewrite.h
index 1f81778e13..877853c09e 100755
--- a/src/main/flight/navigation_rewrite.h
+++ b/src/main/flight/navigation_rewrite.h
@@ -21,7 +21,6 @@
#include "common/filter.h"
#include "fc/rc_controls.h"
-#include "io/motors.h"
#include "io/gps.h"
#include "flight/pid.h"
@@ -237,14 +236,15 @@ void navigationUsePIDs(const pidProfile_t *pidProfile);
void navigationUseConfig(const navConfig_t *navConfigToUse);
void navigationUseRcControlsConfig(const rcControlsConfig_t *initialRcControlsConfig);
void navigationUseRxConfig(const rxConfig_t * initialRxConfig);
-void navigationUsemotorConfig(const motorConfig_t * initialmotorConfig);
+struct motorConfig_s;
+void navigationUsemotorConfig(const struct motorConfig_s * initialmotorConfig);
void navigationUseFlight3DConfig(const flight3DConfig_t * initialFlight3DConfig);
void navigationInit(const navConfig_t *initialnavConfig,
const pidProfile_t *initialPidProfile,
const rcControlsConfig_t *initialRcControlsConfig,
const rxConfig_t * initialRxConfig,
const flight3DConfig_t * initialFlight3DConfig,
- const motorConfig_t * initialmotorConfig);
+ const struct motorConfig_s * initialmotorConfig);
/* Navigation system updates */
void updateWaypointsAndNavigationMode(void);
diff --git a/src/main/flight/navigation_rewrite_multicopter.c b/src/main/flight/navigation_rewrite_multicopter.c
index b69898dfbd..92f0e190b0 100755
--- a/src/main/flight/navigation_rewrite_multicopter.c
+++ b/src/main/flight/navigation_rewrite_multicopter.c
@@ -36,8 +36,6 @@
#include "sensors/acceleration.h"
#include "sensors/boardalignment.h"
-#include "io/motors.h"
-
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
diff --git a/src/main/flight/navigation_rewrite_private.h b/src/main/flight/navigation_rewrite_private.h
index 98421741c2..1d2b9905c5 100755
--- a/src/main/flight/navigation_rewrite_private.h
+++ b/src/main/flight/navigation_rewrite_private.h
@@ -246,7 +246,7 @@ typedef struct {
navigationFSMState_t onEvent[NAV_FSM_EVENT_COUNT];
} navigationFSMStateDescriptor_t;
-
+struct motorConfig_s;
typedef struct {
/* Flags and navigation system state */
navigationFSMState_t navState;
@@ -291,7 +291,7 @@ typedef struct {
const pidProfile_t * pidProfile;
const rxConfig_t * rxConfig;
const flight3DConfig_t * flight3DConfig;
- const motorConfig_t * motorConfig;
+ const struct motorConfig_s * motorConfig;
} navigationPosControl_t;
extern navigationPosControl_t posControl;
diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c
index c1b336035e..813e0ad271 100644
--- a/src/main/flight/pid.c
+++ b/src/main/flight/pid.c
@@ -39,7 +39,6 @@
#include "flight/navigation_rewrite.h"
#include "io/gps.h"
-#include "io/motors.h"
#include "rx/rx.h"
diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c
index dff9ff3393..aedc2d11f5 100755
--- a/src/main/flight/servos.c
+++ b/src/main/flight/servos.c
@@ -39,7 +39,6 @@
#include "drivers/system.h"
#include "io/gimbal.h"
-#include "io/servos.h"
#include "rx/rx.h"
@@ -67,6 +66,13 @@ extern const mixer_t mixers[];
servoMixerConfig_t *servoMixerConfig;
+PG_REGISTER_WITH_RESET_TEMPLATE(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0);
+
+PG_RESET_TEMPLATE(servoConfig_t, servoConfig,
+ .servoCenterPulse = 1500,
+ .servoPwmRate = 50,
+);
+
static uint8_t servoRuleCount = 0;
static servoMixer_t currentServoMixer[MAX_SERVO_RULES];
int16_t servo[MAX_SUPPORTED_SERVOS];
diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h
index cb6efd467f..21131e067e 100644
--- a/src/main/flight/servos.h
+++ b/src/main/flight/servos.h
@@ -107,6 +107,14 @@ typedef struct servoParam_s {
uint32_t reversedSources; // the direction of servo movement for each input source of the servo mixer, bit set=inverted
} __attribute__ ((__packed__)) servoParam_t;
+typedef struct servoConfig_s {
+ // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
+ uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
+ uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
+} servoConfig_t;
+
+PG_DECLARE(servoConfig_t, servoConfig);
+
extern int16_t servo[MAX_SUPPORTED_SERVOS];
bool isServoOutputEnabled(void);
diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c
index 56f998bfc4..b411f85c24 100644
--- a/src/main/io/ledstrip.c
+++ b/src/main/io/ledstrip.c
@@ -55,8 +55,6 @@
#include "io/ledstrip.h"
#include "io/beeper.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/gimbal.h"
#include "io/serial.h"
#include "io/gps.h"
diff --git a/src/main/io/motors.c b/src/main/io/motors.c
deleted file mode 100644
index 13446ef076..0000000000
--- a/src/main/io/motors.c
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * 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 .
- */
-
-#include
-
-#include "platform.h"
-
-#include "config/parameter_group.h"
-#include "config/parameter_group_ids.h"
-
-#include "drivers/pwm_output.h"
-
-#include "io/motors.h"
-
-#ifdef BRUSHED_MOTORS
-#define DEFAULT_PWM_PROTOCOL PWM_TYPE_BRUSHED
-#define DEFAULT_PWM_RATE 16000
-#define DEFAULT_MIN_THROTTLE 1000
-#else
-#define DEFAULT_PWM_PROTOCOL PWM_TYPE_STANDARD
-#define DEFAULT_PWM_RATE 400
-#define DEFAULT_MIN_THROTTLE 1150
-#endif
-
-PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 1);
-
-PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
- .minthrottle = DEFAULT_MIN_THROTTLE,
- .motorPwmProtocol = DEFAULT_PWM_PROTOCOL,
- .motorPwmRate = DEFAULT_PWM_RATE,
- .maxthrottle = 1850,
- .mincommand = 1000
-);
diff --git a/src/main/io/motors.h b/src/main/io/motors.h
deleted file mode 100644
index 29bbf48363..0000000000
--- a/src/main/io/motors.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * 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 .
- */
-
-#pragma once
-
-#include "config/parameter_group.h"
-
-typedef struct motorConfig_s {
- // PWM values, in milliseconds, common range is 1000-2000 (1ms 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 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 motorPwmRate; // The update rate of motor outputs (50-498Hz)
- uint8_t motorPwmProtocol;
-} motorConfig_t;
-
-PG_DECLARE(motorConfig_t, motorConfig);
diff --git a/src/main/io/servos.h b/src/main/io/servos.h
deleted file mode 100644
index 927b067e28..0000000000
--- a/src/main/io/servos.h
+++ /dev/null
@@ -1,24 +0,0 @@
-/*
- * 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 .
- */
-
-#pragma once
-
-typedef struct servoConfig_s {
- // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
- uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
- uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
-} servoConfig_t;
diff --git a/src/main/target/COLIBRI/config.c b/src/main/target/COLIBRI/config.c
index 03d65abe13..e2541a038a 100755
--- a/src/main/target/COLIBRI/config.c
+++ b/src/main/target/COLIBRI/config.c
@@ -49,8 +49,6 @@
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/ledstrip.h"
#include "io/gps.h"
diff --git a/src/main/target/COLIBRI_RACE/config.c b/src/main/target/COLIBRI_RACE/config.c
index 74935f3419..3f189bebf7 100755
--- a/src/main/target/COLIBRI_RACE/config.c
+++ b/src/main/target/COLIBRI_RACE/config.c
@@ -49,8 +49,6 @@
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "io/ledstrip.h"
#include "io/gps.h"
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 2508962a9c..5ce127e460 100755
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -44,8 +44,6 @@
#include "io/gimbal.h"
#include "io/gps.h"
#include "io/ledstrip.h"
-#include "io/motors.h"
-#include "io/servos.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h"