mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-16 21:05:32 +03:00
Added servoConfig parameter group
This commit is contained in:
parent
90d03d114a
commit
54db3efe21
29 changed files with 77 additions and 160 deletions
1
Makefile
1
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 \
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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"
|
||||
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -45,7 +45,6 @@
|
|||
|
||||
#include "io/gps.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/motors.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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];
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -39,7 +39,6 @@
|
|||
#include "flight/navigation_rewrite.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/motors.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
|
|
@ -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];
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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"
|
||||
|
|
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#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
|
||||
);
|
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#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);
|
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#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;
|
|
@ -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"
|
||||
|
||||
|
|
|
@ -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"
|
||||
|
||||
|
|
|
@ -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"
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue