1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

Feature SERVO_TILT removed

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-05-08 15:14:41 +02:00
parent 2aac86663d
commit 392e31a9a5
7 changed files with 27 additions and 50 deletions

View file

@ -341,7 +341,7 @@ Re-apply any new defaults as desired.
| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | | yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | | throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. |
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. | | flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
| gimbal_mode | NORMAL | When feature SERVO_TILT is enabled, this can be either NORMAL or MIXTILT | | gimbal_mode | NORMAL | This can be either NORMAL or MIXTILT. NORMAL mean each axis is outputed to separated servos. MIXTILT combines PITCH and ROLL. Refer to gimbal documentation |
| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. | | fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. |
| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. | | fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. |
| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter | | fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter |

View file

@ -141,7 +141,7 @@ static const char* const emptyName = "-";
// sync this with features_e // sync this with features_e
static const char * const featureNames[] = { static const char * const featureNames[] = {
"RX_PPM", "VBAT", "TX_PROF_SEL", "", "MOTOR_STOP", "RX_PPM", "VBAT", "TX_PROF_SEL", "", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "GPS", "", "", "SOFTSERIAL", "GPS", "",
"", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "",
"BLACKBOX", "", "TRANSPONDER", "AIRMODE", "BLACKBOX", "", "TRANSPONDER", "AIRMODE",

View file

@ -48,7 +48,7 @@ typedef enum {
FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command
FEATURE_UNUSED_2 = 1 << 3, // RX_SERIAL FEATURE_UNUSED_2 = 1 << 3, // RX_SERIAL
FEATURE_MOTOR_STOP = 1 << 4, FEATURE_MOTOR_STOP = 1 << 4,
FEATURE_SERVO_TILT = 1 << 5, NOT_USED_10 = 1 << 5, // was FEATURE_SERVO_TILT
FEATURE_SOFTSERIAL = 1 << 6, FEATURE_SOFTSERIAL = 1 << 6,
FEATURE_GPS = 1 << 7, FEATURE_GPS = 1 << 7,
FEATURE_UNUSED_3 = 1 << 8, // was FEATURE_FAILSAFE FEATURE_UNUSED_3 = 1 << 8, // was FEATURE_FAILSAFE
@ -63,13 +63,13 @@ typedef enum {
FEATURE_DASHBOARD = 1 << 17, FEATURE_DASHBOARD = 1 << 17,
FEATURE_UNUSED_7 = 1 << 18, // Unused in INAV FEATURE_UNUSED_7 = 1 << 18, // Unused in INAV
FEATURE_BLACKBOX = 1 << 19, FEATURE_BLACKBOX = 1 << 19,
FEATURE_UNUSED_10 = 1 << 20, // was FEATURE_CHANNEL_FORWARDING FEATURE_UNUSED_10 = 1 << 20, // was FEATURE_CHANNEL_FORWARDING
FEATURE_TRANSPONDER = 1 << 21, FEATURE_TRANSPONDER = 1 << 21,
FEATURE_AIRMODE = 1 << 22, FEATURE_AIRMODE = 1 << 22,
FEATURE_SUPEREXPO_RATES = 1 << 23, FEATURE_SUPEREXPO_RATES = 1 << 23,
FEATURE_VTX = 1 << 24, FEATURE_VTX = 1 << 24,
FEATURE_UNUSED_8 = 1 << 25, // RX_SPI FEATURE_UNUSED_8 = 1 << 25, // RX_SPI
FEATURE_UNUSED_9 = 1 << 26, //SOFTSPI FEATURE_UNUSED_9 = 1 << 26, //SOFTSPI
FEATURE_PWM_SERVO_DRIVER = 1 << 27, FEATURE_PWM_SERVO_DRIVER = 1 << 27,
FEATURE_PWM_OUTPUT_ENABLE = 1 << 28, FEATURE_PWM_OUTPUT_ENABLE = 1 << 28,
FEATURE_OSD = 1 << 29, FEATURE_OSD = 1 << 29,

View file

@ -802,11 +802,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
processServoAutotrim(); processServoAutotrim();
} }
// Servo tilt is not part of servo mixer, but uses servos
if (feature(FEATURE_SERVO_TILT)) {
processServoTilt();
}
//Servos should be filtered or written only when mixer is using servos or special feaures are enabled //Servos should be filtered or written only when mixer is using servos or special feaures are enabled
if (isServoOutputEnabled()) { if (isServoOutputEnabled()) {
writeServos(); writeServos();

View file

@ -173,8 +173,8 @@ void initActiveBoxIds(void)
activeBoxIds[activeBoxIdCount++] = BOXHEADADJ; activeBoxIds[activeBoxIdCount++] = BOXHEADADJ;
} }
if (feature(FEATURE_SERVO_TILT)) //Camstab mode is enabled always
activeBoxIds[activeBoxIdCount++] = BOXCAMSTAB; activeBoxIds[activeBoxIdCount++] = BOXCAMSTAB;
#ifdef USE_GPS #ifdef USE_GPS
if (sensors(SENSOR_BARO) || (STATE(FIXED_WING) && feature(FEATURE_GPS))) { if (sensors(SENSOR_BARO) || (STATE(FIXED_WING) && feature(FEATURE_GPS))) {

View file

@ -95,7 +95,6 @@ void mixerUpdateStateFlags(void);
void mixerResetDisarmedMotors(void); void mixerResetDisarmedMotors(void);
void mixTable(void); void mixTable(void);
void writeMotors(void); void writeMotors(void);
void processServoTilt(void);
void processServoAutotrim(void); void processServoAutotrim(void);
void stopMotors(void); void stopMotors(void);
void stopPwmAllMotors(void); void stopPwmAllMotors(void);

View file

@ -143,9 +143,6 @@ void servosInit(void)
mixerUsesServos = 1; mixerUsesServos = 1;
} }
// enable servos for mixes that require them. note, this shifts motor counts.
servoOutputEnabled = mixerUsesServos || feature(FEATURE_SERVO_TILT);
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++)
servoComputeScalingFactors(i); servoComputeScalingFactors(i);
@ -214,7 +211,6 @@ void writeServos(void)
filterServos(); filterServos();
int servoIndex = 0; int servoIndex = 0;
bool zeroServoValue = false; bool zeroServoValue = false;
/* /*
@ -224,22 +220,13 @@ void writeServos(void)
zeroServoValue = true; zeroServoValue = true;
} }
// Write mixer servo outputs for (int i = minServoIndex; i <= maxServoIndex; i++) {
// mixerUsesServos might indicate SERVO_TILT, servoRuleCount indicate if mixer alone uses servos if (zeroServoValue) {
if (mixerUsesServos && servoRuleCount) { pwmWriteServo(servoIndex++, 0);
for (int i = minServoIndex; i <= maxServoIndex; i++) { } else {
if (zeroServoValue) { pwmWriteServo(servoIndex++, servo[i]);
pwmWriteServo(servoIndex++, 0);
} else {
pwmWriteServo(servoIndex++, servo[i]);
}
} }
} }
if (feature(FEATURE_SERVO_TILT)) {
pwmWriteServo(servoIndex++, servo[SERVO_GIMBAL_PITCH]);
pwmWriteServo(servoIndex++, servo[SERVO_GIMBAL_ROLL]);
}
} }
void servoMixer(float dT) void servoMixer(float dT)
@ -265,8 +252,21 @@ void servoMixer(float dT)
input[INPUT_FEATURE_FLAPS] = FLIGHT_MODE(FLAPERON) ? servoConfig()->flaperon_throw_offset : 0; input[INPUT_FEATURE_FLAPS] = FLIGHT_MODE(FLAPERON) ? servoConfig()->flaperon_throw_offset : 0;
input[INPUT_GIMBAL_PITCH] = scaleRange(attitude.values.pitch, -1800, 1800, -500, +500); if (IS_RC_MODE_ACTIVE(BOXCAMSTAB)) {
input[INPUT_GIMBAL_ROLL] = scaleRange(attitude.values.roll, -1800, 1800, -500, +500); const int gimbalPitch = scaleRange(attitude.values.pitch, -1800, 1800, -360, +360);
const int gimbalRoll = scaleRange(attitude.values.roll, -1800, 1800, -360, +360);
if (gimbalConfig()->mode == GIMBAL_MODE_MIXTILT) {
input[INPUT_GIMBAL_PITCH] = gimbalPitch - gimbalRoll;
input[INPUT_GIMBAL_ROLL] = gimbalPitch + gimbalRoll;
} else {
input[INPUT_GIMBAL_PITCH] = gimbalPitch;
input[INPUT_GIMBAL_ROLL] = gimbalRoll;
}
} else {
input[INPUT_GIMBAL_PITCH] = 0;
input[INPUT_GIMBAL_ROLL] = 0;
}
input[INPUT_STABILIZED_THROTTLE] = motor[0] - 1000 - 500; // Since it derives from rcCommand or mincommand and must be [-500:+500] input[INPUT_STABILIZED_THROTTLE] = motor[0] - 1000 - 500; // Since it derives from rcCommand or mincommand and must be [-500:+500]
@ -346,23 +346,6 @@ void servoMixer(float dT)
} }
} }
void processServoTilt(void)
{
// center at fixed position, or vary either pitch or roll by RC channel
servo[SERVO_GIMBAL_PITCH] = servoParams(SERVO_GIMBAL_PITCH)->middle;
servo[SERVO_GIMBAL_ROLL] = servoParams(SERVO_GIMBAL_PITCH)->middle;
if (IS_RC_MODE_ACTIVE(BOXCAMSTAB)) {
if (gimbalConfig()->mode == GIMBAL_MODE_MIXTILT) {
servo[SERVO_GIMBAL_PITCH] -= (-(int32_t)servoParams(SERVO_GIMBAL_PITCH)->rate) * attitude.values.pitch / 50 - (int32_t)servoParams(SERVO_GIMBAL_ROLL)->rate * attitude.values.roll / 50;
servo[SERVO_GIMBAL_ROLL] += (-(int32_t)servoParams(SERVO_GIMBAL_PITCH)->rate) * attitude.values.pitch / 50 + (int32_t)servoParams(SERVO_GIMBAL_ROLL)->rate * attitude.values.roll / 50;
} else {
servo[SERVO_GIMBAL_PITCH] += (int32_t)servoParams(SERVO_GIMBAL_PITCH)->rate * attitude.values.pitch / 50;
servo[SERVO_GIMBAL_ROLL] += (int32_t)servoParams(SERVO_GIMBAL_ROLL)->rate * attitude.values.roll / 50;
}
}
}
#define SERVO_AUTOTRIM_TIMER_MS 2000 #define SERVO_AUTOTRIM_TIMER_MS 2000
typedef enum { typedef enum {