Added injection for GPS rescue commands.
This commit is contained in:
parent
ce4a95f33d
commit
f129f7913c
|
@ -974,6 +974,7 @@ static FAST_CODE void subTaskMotorUpdate(timeUs_t currentTimeUs)
|
|||
|
||||
static FAST_CODE_NOINLINE void subTaskRcCommand(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
// If we're armed, at minimum throttle, and we do arming via the
|
||||
// sticks, do not process yaw input from the rx. We do this so the
|
||||
|
@ -996,7 +997,12 @@ static FAST_CODE_NOINLINE void subTaskRcCommand(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
processRcCommand();
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
#if defined(USE_GPS_RESCUE)
|
||||
if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
|
||||
gpsRescueInjectRcCommands();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// Function for loop trigger
|
||||
|
|
|
@ -43,7 +43,6 @@
|
|||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/gps_rescue.h"
|
||||
#include "flight/pid.h"
|
||||
#include "pg/rx.h"
|
||||
#include "rx/rx.h"
|
||||
|
@ -528,10 +527,6 @@ FAST_CODE FAST_CODE_NOINLINE void updateRcCommands(void)
|
|||
rcCommand[YAW] = rcCommandBuff.Z;
|
||||
}
|
||||
}
|
||||
|
||||
if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
|
||||
rcCommand[THROTTLE] = rescueThrottle;
|
||||
}
|
||||
}
|
||||
|
||||
void resetYawAxis(void)
|
||||
|
|
|
@ -71,6 +71,9 @@ PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig,
|
|||
.minSats = 8
|
||||
);
|
||||
|
||||
static uint16_t rescueThrottle;
|
||||
static uint16_t rescueYaw;
|
||||
|
||||
int32_t gpsRescueAngle[ANGLE_INDEX_COUNT] = { 0, 0 };
|
||||
uint16_t hoverThrottle = 0;
|
||||
float averageThrottle = 0.0;
|
||||
|
@ -398,7 +401,13 @@ void setBearing(int16_t deg)
|
|||
|
||||
dif *= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed);
|
||||
|
||||
rcCommand[YAW] = - (dif * gpsRescueConfig()->yawP / 20);
|
||||
rescueYaw = - (dif * gpsRescueConfig()->yawP / 20);
|
||||
}
|
||||
|
||||
void gpsRescueInjectRcCommands(void)
|
||||
{
|
||||
rcCommand[THROTTLE] = rescueThrottle;
|
||||
rcCommand[YAW] = rescueYaw;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -42,8 +42,6 @@ typedef struct gpsRescue_s {
|
|||
|
||||
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);
|
||||
|
||||
uint16_t rescueThrottle;
|
||||
|
||||
typedef enum {
|
||||
RESCUE_IDLE,
|
||||
RESCUE_INITIALIZE,
|
||||
|
@ -110,3 +108,5 @@ void performSanityChecks(void);
|
|||
void sensorUpdate(void);
|
||||
|
||||
void rescueAttainPosition(void);
|
||||
|
||||
void gpsRescueInjectRcCommands(void);
|
||||
|
|
Loading…
Reference in New Issue