mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Use autopilotAngle in place of posHoldAngle
This commit is contained in:
parent
9a80b75abe
commit
35d3006ecd
4 changed files with 10 additions and 10 deletions
|
@ -77,7 +77,7 @@ static posHoldState posHold = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static gpsLocation_t currentTargetLocation = {0, 0, 0};
|
static gpsLocation_t currentTargetLocation = {0, 0, 0};
|
||||||
float posHoldAngle[ANGLE_INDEX_COUNT];
|
float autopilotAngle[ANGLE_INDEX_COUNT];
|
||||||
static pt1Filter_t velocityPitchLpf;
|
static pt1Filter_t velocityPitchLpf;
|
||||||
static pt1Filter_t accelerationPitchLpf;
|
static pt1Filter_t accelerationPitchLpf;
|
||||||
static pt1Filter_t velocityRollLpf;
|
static pt1Filter_t velocityRollLpf;
|
||||||
|
@ -328,25 +328,25 @@ bool positionControl(bool useStickAdjustment, float deadband) {
|
||||||
// if done in pid.c, the same upsampler could be used for GPS and PosHold.
|
// if done in pid.c, the same upsampler could be used for GPS and PosHold.
|
||||||
|
|
||||||
// if a deadband is set, and sticks are outside deadband, allow pilot control, otherwise hold position
|
// if a deadband is set, and sticks are outside deadband, allow pilot control, otherwise hold position
|
||||||
posHoldAngle[AI_ROLL] = (useStickAdjustment && getRcDeflectionAbs(FD_ROLL) > deadband) ? 0.0f : pidSumRoll;
|
autopilotAngle[AI_ROLL] = (useStickAdjustment && getRcDeflectionAbs(FD_ROLL) > deadband) ? 0.0f : pidSumRoll;
|
||||||
posHoldAngle[AI_PITCH] = (useStickAdjustment && getRcDeflectionAbs(FD_PITCH) > deadband) ? 0.0f : pidSumPitch;
|
autopilotAngle[AI_PITCH] = (useStickAdjustment && getRcDeflectionAbs(FD_PITCH) > deadband) ? 0.0f : pidSumPitch;
|
||||||
|
|
||||||
// note:
|
// note:
|
||||||
// if FLIGHT_MODE(POS_HOLD_MODE):
|
// if FLIGHT_MODE(POS_HOLD_MODE):
|
||||||
// posHoldAngle[] is added to angle setpoint in pid.c, in degrees
|
// autopilotAngle[] is added to angle setpoint in pid.c, in degrees
|
||||||
// stick angle setpoint forced to zero within the same deadband via rc.c
|
// stick angle setpoint forced to zero within the same deadband via rc.c
|
||||||
|
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 0, lrintf(normalisedErrorAngle));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 0, lrintf(normalisedErrorAngle));
|
||||||
if (gyroConfig()->gyro_filter_debug_axis == FD_ROLL) {
|
if (gyroConfig()->gyro_filter_debug_axis == FD_ROLL) {
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 1, lrintf(-distanceRoll));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 1, lrintf(-distanceRoll));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 2, lrintf(posHoldAngle[AI_ROLL] * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 2, lrintf(autopilotAngle[AI_ROLL] * 10));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 4, lrintf(rollP * 10)); // degrees*10
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 4, lrintf(rollP * 10)); // degrees*10
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 5, lrintf(posHold.rollI * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 5, lrintf(posHold.rollI * 10));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 6, lrintf(rollD * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 6, lrintf(rollD * 10));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 7, lrintf(rollJ * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 7, lrintf(rollJ * 10));
|
||||||
} else {
|
} else {
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 1, lrintf(-distancePitch));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 1, lrintf(-distancePitch));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 2, lrintf(posHoldAngle[AI_PITCH] * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 2, lrintf(autopilotAngle[AI_PITCH] * 10));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 4, lrintf(pitchP * 10)); // degrees*10
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 4, lrintf(pitchP * 10)); // degrees*10
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 5, lrintf(posHold.pitchI * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 5, lrintf(posHold.pitchI * 10));
|
||||||
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 6, lrintf(pitchD * 10));
|
DEBUG_SET(DEBUG_AUTOPILOT_POSITION, 6, lrintf(pitchD * 10));
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
|
||||||
extern float posHoldAngle[ANGLE_INDEX_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
|
extern float autopilotAngle[ANGLE_INDEX_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
|
||||||
|
|
||||||
void autopilotInit(const autopilotConfig_t *config);
|
void autopilotInit(const autopilotConfig_t *config);
|
||||||
void resetAltitudeControl(void);
|
void resetAltitudeControl(void);
|
||||||
|
|
|
@ -569,7 +569,7 @@ STATIC_UNIT_TESTED FAST_CODE_NOINLINE float pidLevel(int axis, const pidProfile_
|
||||||
angleTarget += gpsRescueAngle[axis] / 100.0f; // Angle is in centidegrees, stepped on roll at 10Hz but not on pitch
|
angleTarget += gpsRescueAngle[axis] / 100.0f; // Angle is in centidegrees, stepped on roll at 10Hz but not on pitch
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_POS_HOLD_MODE
|
#ifdef USE_POS_HOLD_MODE
|
||||||
angleTarget += posHoldAngle[axis]; // posHoldAngle is in degrees, stepped at 10Hz
|
angleTarget += autopilotAngle[axis]; // autopilotAngle is in degrees, stepped at 10Hz
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const float currentAngle = (attitude.raw[axis] - angleTrim->raw[axis]) / 10.0f; // stepped at 500hz with some 4ms flat spots
|
const float currentAngle = (attitude.raw[axis] - angleTrim->raw[axis]) / 10.0f; // stepped at 500hz with some 4ms flat spots
|
||||||
|
|
|
@ -85,8 +85,8 @@ void posHoldNewGpsData(void) {
|
||||||
posHold.posHoldIsOK = positionControl(posHold.useStickAdjustment, posHold.deadband);
|
posHold.posHoldIsOK = positionControl(posHold.useStickAdjustment, posHold.deadband);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
posHoldAngle[AI_PITCH] = 0.0f;
|
autopilotAngle[AI_PITCH] = 0.0f;
|
||||||
posHoldAngle[AI_ROLL] = 0.0f;
|
autopilotAngle[AI_ROLL] = 0.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue