1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00

Separate autopilot multirotor from autopilot wing - dummy files for wing (#14108)

* separate autopilot multirotor from autopilot wing - dummy files for wing

* fix for lisence header for new files

* filling empty PG structures with uint8_t dummy
This commit is contained in:
Ivan Efimov 2024-12-30 15:36:33 -06:00 committed by GitHub
parent 2a50634f67
commit ef81595f1d
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
48 changed files with 1345 additions and 194 deletions

View file

@ -1,7 +1,9 @@
PG_SRC = \
pg/adc.c \
pg/alt_hold.c \
pg/autopilot.c \
pg/alt_hold_multirotor.c \
pg/alt_hold_wing.c \
pg/autopilot_multirotor.c \
pg/autopilot_wing.c \
pg/beeper.c \
pg/beeper_dev.c \
pg/board.c \
@ -15,7 +17,8 @@ PG_SRC = \
pg/gimbal.c \
pg/gps.c \
pg/gps_lap_timer.c \
pg/gps_rescue.c \
pg/gps_rescue_multirotor.c \
pg/gps_rescue_wing.c \
pg/gyrodev.c \
pg/max7456.c \
pg/mco.c \
@ -26,7 +29,8 @@ PG_SRC = \
pg/piniobox.c \
pg/pinio.c \
pg/pin_pull_up_down.c \
pg/pos_hold.c \
pg/pos_hold_multirotor.c \
pg/pos_hold_wing.c \
pg/rcdevice.c \
pg/rpm_filter.c \
pg/rx.c \
@ -154,11 +158,14 @@ COMMON_SRC = \
fc/rc_adjustments.c \
fc/rc_controls.c \
fc/rc_modes.c \
flight/alt_hold.c \
flight/autopilot.c \
flight/alt_hold_multirotor.c \
flight/alt_hold_wing.c \
flight/autopilot_multirotor.c \
flight/autopilot_wing.c \
flight/dyn_notch_filter.c \
flight/failsafe.c \
flight/gps_rescue.c \
flight/gps_rescue_multirotor.c \
flight/gps_rescue_wing.c \
flight/imu.c \
flight/mixer.c \
flight/mixer_init.c \
@ -166,7 +173,8 @@ COMMON_SRC = \
flight/pid.c \
flight/pid_init.c \
flight/position.c \
flight/pos_hold.c \
flight/pos_hold_multirotor.c \
flight/pos_hold_wing.c \
flight/rpm_filter.c \
flight/servos.c \
flight/servos_tricopter.c \
@ -210,7 +218,8 @@ COMMON_SRC = \
cms/cms_menu_blackbox.c \
cms/cms_menu_failsafe.c \
cms/cms_menu_firmware.c \
cms/cms_menu_gps_rescue.c \
cms/cms_menu_gps_rescue_multirotor.c \
cms/cms_menu_gps_rescue_wing.c \
cms/cms_menu_gps_lap_timer.c \
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
@ -513,7 +522,8 @@ SIZE_OPTIMISED_SRC += \
cms/cms_menu_blackbox.c \
cms/cms_menu_failsafe.c \
cms/cms_menu_firmware.c \
cms/cms_menu_gps_rescue.c \
cms/cms_menu_gps_rescue_multirotor.c \
cms/cms_menu_gps_rescue_wing.c \
cms/cms_menu_gps_lap_timer.c \
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \

View file

@ -745,7 +745,7 @@ static void writeIntraframe(void)
if (testBlackboxCondition(CONDITION(ACC))) {
blackboxWriteSigned16VBArray(blackboxCurrent->accADC, XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(CONDITION(ATTITUDE))) {
blackboxWriteSigned16VBArray(blackboxCurrent->imuAttitudeQuaternion, XYZ_AXIS_COUNT);
}
@ -930,7 +930,7 @@ static void writeInterframe(void)
if (testBlackboxCondition(CONDITION(ACC))) {
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(CONDITION(ATTITUDE))) {
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, imuAttitudeQuaternion), XYZ_AXIS_COUNT);
}
@ -1244,14 +1244,14 @@ static void loadMainState(timeUs_t currentTimeUs)
blackboxCurrent->axisPID_F[i] = lrintf(pidData[i].F);
#ifdef USE_WING
blackboxCurrent->axisPID_S[i] = lrintf(pidData[i].S);
#endif
#endif
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i] * blackboxHighResolutionScale);
blackboxCurrent->gyroUnfilt[i] = lrintf(gyro.gyroADC[i] * blackboxHighResolutionScale);
#if defined(USE_ACC)
blackboxCurrent->accADC[i] = lrintf(acc.accADC.v[i]);
STATIC_ASSERT(offsetof(quaternion_t, w) == 0, "Code expects quaternion in w, x, y, z order");
blackboxCurrent->imuAttitudeQuaternion[i] = lrintf(imuAttitudeQuaternion.v[i + 1] * 0x7FFF); //Scale to int16 by value 0x7FFF = 2^15 - 1; Use i+1 index for x,y,z components access, [0] - w
blackboxCurrent->imuAttitudeQuaternion[i] = lrintf(imuAttitudeQuaternion.v[i + 1] * 0x7FFF); //Scale to int16 by value 0x7FFF = 2^15 - 1; Use i+1 index for x,y,z components access, [0] - w
#endif
#ifdef USE_MAG
blackboxCurrent->magADC[i] = lrintf(mag.magADC.v[i]);
@ -1695,6 +1695,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_LPF, "%d", positionConfig()->altitude_lpf);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_D_LPF, "%d", positionConfig()->altitude_d_lpf);
#ifndef USE_WING
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_LANDING_ALTITUDE, "%d", apConfig()->landing_altitude_m);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_HOVER_THROTTLE, "%d", apConfig()->hover_throttle);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_MIN, "%d", apConfig()->throttle_min);
@ -1709,6 +1710,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_A, "%d", apConfig()->position_A);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_CUTOFF, "%d", apConfig()->position_cutoff);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_MAX_ANGLE, "%d", apConfig()->max_angle);
#endif // !USE_WING
#ifdef USE_MAG
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MAG_HARDWARE, "%d", compassConfig()->mag_hardware);
@ -1785,6 +1787,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_USE_3D_SPEED, "%d", gpsConfig()->gps_use_3d_speed)
#ifdef USE_GPS_RESCUE
#ifndef USE_WING
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MIN_START_DIST, "%d", gpsRescueConfig()->minStartDistM)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ALT_MODE, "%d", gpsRescueConfig()->altitudeMode)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_INITIAL_CLIMB, "%d", gpsRescueConfig()->initialClimbM)
@ -1809,21 +1812,25 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_I, "%d", gpsRescueConfig()->velI)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_D, "%d", gpsRescueConfig()->velD)
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_YAW_P, "%d", gpsRescueConfig()->yawP)
#ifdef USE_MAG
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_USE_MAG, "%d", gpsRescueConfig()->useMag)
#endif // USE_MAG
#endif // !USE_WING
#endif // USE_GPS_RESCUE
#endif // USE_GPS
#ifdef USE_ALTITUDE_HOLD
#ifndef USE_WING
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALT_HOLD_THROTTLE_RESPONSE, "%d", altHoldConfig()->alt_hold_adjust_rate);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALT_HOLD_DEADBAND, "%d", altHoldConfig()->alt_hold_deadband);
#endif
#endif // !USE_WING
#endif // USE_ALTITUDE_HOLD
#ifdef USE_POSITION_HOLD
#ifndef USE_WING
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POS_HOLD_WITHOUT_MAG, "%d", posHoldConfig()->pos_hold_without_mag);
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POS_HOLD_DEADBAND, "%d", posHoldConfig()->pos_hold_deadband);
#endif // !USE_WING
#endif
#ifdef USE_WING

View file

@ -1074,6 +1074,7 @@ const clivalue_t valueTable[] = {
{ PARAM_NAME_GPS_NMEA_CUSTOM_COMMANDS, VAR_UINT8 | MASTER_VALUE | MODE_STRING, .config.string = { 1, NMEA_CUSTOM_COMMANDS_MAX_LENGTH, STRING_FLAGS_NONE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, nmeaCustomCommands) },
#ifdef USE_GPS_RESCUE
#ifndef USE_WING
// PG_GPS_RESCUE
{ PARAM_NAME_GPS_RESCUE_MIN_START_DIST, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 30 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, minStartDistM) },
{ PARAM_NAME_GPS_RESCUE_ALT_MODE, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_RESCUE_ALT_MODE }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, altitudeMode) },
@ -1103,6 +1104,7 @@ const clivalue_t valueTable[] = {
#ifdef USE_MAG
{ PARAM_NAME_GPS_RESCUE_USE_MAG, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, useMag) },
#endif // USE_MAG
#endif // !USE_WING
#endif // USE_GPS_RESCUE
#ifdef USE_GPS_LAP_TIMER
@ -1119,14 +1121,18 @@ const clivalue_t valueTable[] = {
{ "yaw_control_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_control_reversed) },
#ifdef USE_ALTITUDE_HOLD
#ifndef USE_WING
{ PARAM_NAME_ALT_HOLD_THROTTLE_RESPONSE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_ALTHOLD_CONFIG, offsetof(altHoldConfig_t, alt_hold_adjust_rate) },
{ PARAM_NAME_ALT_HOLD_DEADBAND, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 70 }, PG_ALTHOLD_CONFIG, offsetof(altHoldConfig_t, alt_hold_deadband) },
#endif
#endif // !USE_WING
#endif // USE_ALTITUDE_HOLD
#ifdef USE_POSITION_HOLD
#ifndef USE_WING
{ PARAM_NAME_POS_HOLD_WITHOUT_MAG, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_POSHOLD_CONFIG, offsetof(posHoldConfig_t, pos_hold_without_mag) },
{ PARAM_NAME_POS_HOLD_DEADBAND, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 50 }, PG_POSHOLD_CONFIG, offsetof(posHoldConfig_t, pos_hold_deadband) },
#endif
#endif // !USE_WING
#endif // USE_POSITION_HOLD
// PG_PID_CONFIG
{ PARAM_NAME_PID_PROCESS_DENOM, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, MAX_PID_PROCESS_DENOM }, PG_PID_CONFIG, offsetof(pidConfig_t, pid_process_denom) },
@ -1867,6 +1873,7 @@ const clivalue_t valueTable[] = {
{ PARAM_NAME_ALTITUDE_D_LPF, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 1000 }, PG_POSITION, offsetof(positionConfig_t, altitude_d_lpf) },
// PG_AUTOPILOT
#ifndef USE_WING
{ PARAM_NAME_LANDING_ALTITUDE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, landing_altitude_m) },
{ PARAM_NAME_HOVER_THROTTLE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1100, 1700 }, PG_AUTOPILOT, offsetof(apConfig_t, hover_throttle) },
{ PARAM_NAME_THROTTLE_MIN, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1050, 1400 }, PG_AUTOPILOT, offsetof(apConfig_t, throttle_min) },
@ -1881,6 +1888,7 @@ const clivalue_t valueTable[] = {
{ PARAM_NAME_POSITION_A, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, position_A) },
{ PARAM_NAME_POSITION_CUTOFF, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 250 }, PG_AUTOPILOT, offsetof(apConfig_t, position_cutoff) },
{ PARAM_NAME_AP_MAX_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 70 }, PG_AUTOPILOT, offsetof(apConfig_t, max_angle) },
#endif // !USE_WING
// PG_MODE_ACTIVATION_CONFIG
#if defined(USE_CUSTOM_BOX_NAMES)

View file

@ -25,6 +25,8 @@
#include "platform.h"
#ifndef USE_WING
#ifdef USE_CMS_GPS_RESCUE_MENU
#include "cli/settings.h"
@ -242,3 +244,5 @@ CMS_Menu cmsx_menuGpsRescue = {
};
#endif
#endif // !USE_WING

View file

@ -0,0 +1,114 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#ifdef USE_WING
#ifdef USE_CMS_GPS_RESCUE_MENU
#include "cli/settings.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "cms/cms_menu_gps_rescue.h"
#include "config/feature.h"
#include "config/config.h"
#include "flight/position.h"
#include "pg/autopilot.h"
#include "pg/gps_rescue.h"
static const void *cms_menuGpsRescuePidOnEnter(displayPort_t *pDisp)
{
UNUSED(pDisp);
return NULL;
}
static const void *cms_menuGpsRescuePidOnExit(displayPort_t *pDisp, const OSD_Entry *self)
{
UNUSED(pDisp);
UNUSED(self);
return NULL;
}
const OSD_Entry cms_menuGpsRescuePidEntries[] =
{
{"--- GPS RESCUE PID---", OME_Label, NULL, NULL},
{"BACK", OME_Back, NULL, NULL},
{NULL, OME_END, NULL, NULL}
};
CMS_Menu cms_menuGpsRescuePid = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUGPSRPID",
.GUARD_type = OME_MENU,
#endif
.onEnter = cms_menuGpsRescuePidOnEnter,
.onExit = cms_menuGpsRescuePidOnExit,
.onDisplayUpdate = NULL,
.entries = cms_menuGpsRescuePidEntries,
};
static const void *cmsx_menuGpsRescueOnEnter(displayPort_t *pDisp)
{
UNUSED(pDisp);
return NULL;
}
static const void *cmsx_menuGpsRescueOnExit(displayPort_t *pDisp, const OSD_Entry *self)
{
UNUSED(pDisp);
UNUSED(self);
return NULL;
}
const OSD_Entry cmsx_menuGpsRescueEntries[] =
{
{"--- GPS RESCUE ---", OME_Label, NULL, NULL},
{"BACK", OME_Back, NULL, NULL},
{NULL, OME_END, NULL, NULL}
};
CMS_Menu cmsx_menuGpsRescue = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUGPSRES",
.GUARD_type = OME_MENU,
#endif
.onEnter = cmsx_menuGpsRescueOnEnter,
.onExit = cmsx_menuGpsRescueOnExit,
.onDisplayUpdate = NULL,
.entries = cmsx_menuGpsRescueEntries,
};
#endif
#endif // USE_WING

View file

@ -17,15 +17,5 @@
#pragma once
#include "pg/alt_hold.h"
#ifdef USE_ALTITUDE_HOLD
#include "common/time.h"
#define ALTHOLD_TASK_RATE_HZ 100 // hz
void altHoldInit(void);
void updateAltHold(timeUs_t currentTimeUs);
bool isAltHoldActive(void);
#endif
#include "flight/alt_hold_multirotor.h"
#include "flight/alt_hold_wing.h"

View file

@ -16,6 +16,9 @@
*/
#include "platform.h"
#ifndef USE_WING
#include "math.h"
#ifdef USE_ALTITUDE_HOLD
@ -90,8 +93,8 @@ void altHoldProcessTransitions(void) {
void altHoldUpdateTargetAltitude(void)
{
// User can adjust the target altitude with throttle, but only when
// - throttle is outside deadband, and
// - throttle is not low (zero), and
// - throttle is outside deadband, and
// - throttle is not low (zero), and
// - deadband is not configured to zero
float stickFactor = 0.0f;
@ -154,3 +157,5 @@ bool isAltHoldActive(void) {
return altHold.isActive;
}
#endif
#endif // !USE_WING

View file

@ -0,0 +1,35 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include "pg/alt_hold.h"
#ifdef USE_ALTITUDE_HOLD
#include "common/time.h"
#define ALTHOLD_TASK_RATE_HZ 100 // hz
void altHoldInit(void);
void updateAltHold(timeUs_t currentTimeUs);
bool isAltHoldActive(void);
#endif
#endif // !USE_WING

View file

@ -0,0 +1,59 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_WING
#include "math.h"
#ifdef USE_ALTITUDE_HOLD
#include "build/debug.h"
#include "common/maths.h"
#include "config/config.h"
#include "fc/rc.h"
#include "fc/runtime_config.h"
#include "flight/autopilot.h"
#include "flight/failsafe.h"
#include "flight/position.h"
#include "rx/rx.h"
#include "pg/autopilot.h"
#include "alt_hold.h"
void altHoldReset(void)
{
}
void altHoldInit(void)
{
}
void updateAltHold(timeUs_t currentTimeUs) {
UNUSED(currentTimeUs);
}
bool isAltHoldActive(void) {
return false;
}
#endif // USE_ALTITUDE_HOLD
#endif // USE_WING

View file

@ -0,0 +1,35 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include "pg/alt_hold.h"
#ifdef USE_ALTITUDE_HOLD
#include "common/time.h"
#define ALTHOLD_TASK_RATE_HZ 100 // hz
void altHoldInit(void);
void updateAltHold(timeUs_t currentTimeUs);
bool isAltHoldActive(void);
#endif
#endif // USE_WING

View file

@ -19,16 +19,5 @@
#include "io/gps.h"
extern float autopilotAngle[RP_AXIS_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
void autopilotInit(void);
void resetAltitudeControl(void);
void setSticksActiveStatus(bool areSticksActive);
void resetPositionControl(const gpsLocation_t *initialTargetLocation, unsigned taskRateHz);
void posControlOutput(void);
bool positionControl(void);
void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAltitudeStep);
bool isBelowLandingAltitude(void);
float getAutopilotThrottle(void);
bool isAutopilotInControl(void);
#include "flight/autopilot_multirotor.h"
#include "flight/autopilot_wing.h"

View file

@ -21,6 +21,9 @@
#include <math.h>
#include "platform.h"
#ifndef USE_WING
#include "build/debug.h"
#include "common/axis.h"
#include "common/filter.h"
@ -395,3 +398,5 @@ bool isAutopilotInControl(void)
{
return !ap.sticksActive;
}
#endif // !USE_WING

View file

@ -0,0 +1,38 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include "io/gps.h"
extern float autopilotAngle[RP_AXIS_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
void autopilotInit(void);
void resetAltitudeControl(void);
void setSticksActiveStatus(bool areSticksActive);
void resetPositionControl(const gpsLocation_t *initialTargetLocation, unsigned taskRateHz);
void posControlOutput(void);
bool positionControl(void);
void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAltitudeStep);
bool isBelowLandingAltitude(void);
float getAutopilotThrottle(void);
bool isAutopilotInControl(void);
#endif // !USE_WING

View file

@ -0,0 +1,91 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <math.h>
#include "platform.h"
#ifdef USE_WING
#include "build/debug.h"
#include "common/axis.h"
#include "common/filter.h"
#include "common/maths.h"
#include "common/vector.h"
#include "fc/rc.h"
#include "fc/runtime_config.h"
#include "flight/imu.h"
#include "flight/position.h"
#include "rx/rx.h"
#include "sensors/gyro.h"
#include "pg/autopilot.h"
#include "autopilot.h"
float autopilotAngle[RP_AXIS_COUNT];
void resetPositionControl(const gpsLocation_t *initialTargetLocation, unsigned taskRateHz)
{
// from pos_hold.c (or other client) when initiating position hold at target location
UNUSED(initialTargetLocation);
UNUSED(taskRateHz);
}
void autopilotInit(void)
{
}
void resetAltitudeControl (void) {
}
void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAltitudeStep)
{
UNUSED(targetAltitudeCm);
UNUSED(taskIntervalS);
UNUSED(targetAltitudeStep);
}
void setSticksActiveStatus(bool areSticksActive)
{
UNUSED(areSticksActive);
}
bool positionControl(void)
{
return false;
}
bool isBelowLandingAltitude(void)
{
return false;
}
float getAutopilotThrottle(void)
{
return 0.0f;
}
bool isAutopilotInControl(void)
{
return false;
}
#endif // USE_WING

View file

@ -0,0 +1,37 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include "io/gps.h"
extern float autopilotAngle[RP_AXIS_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
void autopilotInit(void);
void resetAltitudeControl(void);
void setSticksActiveStatus(bool areSticksActive);
void resetPositionControl(const gpsLocation_t *initialTargetLocation, unsigned taskRateHz);
bool positionControl(void);
void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAltitudeStep);
bool isBelowLandingAltitude(void);
float getAutopilotThrottle(void);
bool isAutopilotInControl(void);
#endif // USE_WING

View file

@ -17,41 +17,5 @@
#pragma once
#include <stdbool.h>
#include "common/axis.h"
#include "pg/gps_rescue.h"
#define TASK_GPS_RESCUE_RATE_HZ 100 // in sync with altitude task rate
#ifdef USE_MAG
#define GPS_RESCUE_USE_MAG true
#else
#define GPS_RESCUE_USE_MAG false
#endif
typedef enum {
RESCUE_SANITY_OFF = 0,
RESCUE_SANITY_ON,
RESCUE_SANITY_FS_ONLY,
RESCUE_SANITY_COUNT
} gpsRescueSanity_e;
typedef enum {
GPS_RESCUE_ALT_MODE_MAX = 0,
GPS_RESCUE_ALT_MODE_FIXED,
GPS_RESCUE_ALT_MODE_CURRENT,
GPS_RESCUE_ALT_MODE_COUNT
} gpsRescueAltitudeMode_e;
extern float gpsRescueAngle[RP_AXIS_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
void gpsRescueInit(void);
void gpsRescueUpdate(void);
float gpsRescueGetYawRate(void);
bool gpsRescueIsConfigured(void);
bool gpsRescueIsAvailable(void);
bool gpsRescueIsDisabled(void);
bool gpsRescueDisableMag(void);
float gpsRescueGetImuYawCogGain(void);
#include "flight/gps_rescue_multirotor.h"
#include "flight/gps_rescue_wing.h"

View file

@ -21,6 +21,7 @@
#include "platform.h"
#ifndef USE_WING
#ifdef USE_GPS_RESCUE
#include "build/debug.h"
@ -138,7 +139,7 @@ void gpsRescueInit(void)
rescueState.intent.velocityPidCutoffModifier = 1.0f;
gain = pt1FilterGain(cutoffHz, 1.0f);
pt1FilterInit(&velocityDLpf, gain);
cutoffHz *= 4.0f;
cutoffHz *= 4.0f;
gain = pt3FilterGain(cutoffHz, taskIntervalSeconds);
pt3FilterInit(&velocityUpsampleLpf, gain);
}
@ -887,3 +888,5 @@ bool gpsRescueDisableMag(void)
}
#endif
#endif
#endif // !USE_WING

View file

@ -0,0 +1,61 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include <stdbool.h>
#include "common/axis.h"
#include "pg/gps_rescue.h"
#define TASK_GPS_RESCUE_RATE_HZ 100 // in sync with altitude task rate
#ifdef USE_MAG
#define GPS_RESCUE_USE_MAG true
#else
#define GPS_RESCUE_USE_MAG false
#endif
typedef enum {
RESCUE_SANITY_OFF = 0,
RESCUE_SANITY_ON,
RESCUE_SANITY_FS_ONLY,
RESCUE_SANITY_COUNT
} gpsRescueSanity_e;
typedef enum {
GPS_RESCUE_ALT_MODE_MAX = 0,
GPS_RESCUE_ALT_MODE_FIXED,
GPS_RESCUE_ALT_MODE_CURRENT,
GPS_RESCUE_ALT_MODE_COUNT
} gpsRescueAltitudeMode_e;
extern float gpsRescueAngle[RP_AXIS_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
void gpsRescueInit(void);
void gpsRescueUpdate(void);
float gpsRescueGetYawRate(void);
bool gpsRescueIsConfigured(void);
bool gpsRescueIsAvailable(void);
bool gpsRescueIsDisabled(void);
bool gpsRescueDisableMag(void);
float gpsRescueGetImuYawCogGain(void);
#endif // !USE_WING

View file

@ -0,0 +1,100 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include <math.h>
#include "platform.h"
#ifdef USE_WING
#ifdef USE_GPS_RESCUE
#include "build/debug.h"
#include "common/axis.h"
#include "common/filter.h"
#include "common/maths.h"
#include "common/utils.h"
#include "config/config.h"
#include "drivers/time.h"
#include "fc/core.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "flight/autopilot.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/pid.h"
#include "flight/position.h"
#include "io/gps.h"
#include "rx/rx.h"
#include "pg/autopilot.h"
#include "sensors/acceleration.h"
#include "gps_rescue.h"
float gpsRescueAngle[RP_AXIS_COUNT] = { 0, 0 };
void gpsRescueInit(void)
{
}
void gpsRescueUpdate(void)
// runs at gpsRescueTaskIntervalSeconds, and runs whether or not rescue is active
{
}
float gpsRescueGetYawRate(void)
{
return 0.0f; // the control yaw value for rc.c to be used while flightMode gps_rescue is active.
}
float gpsRescueGetImuYawCogGain(void)
{
return 1.0f;
}
bool gpsRescueIsConfigured(void)
{
return false;
}
bool gpsRescueIsAvailable(void)
{
return false;
}
bool gpsRescueIsDisabled(void)
{
return true;
}
#ifdef USE_MAG
bool gpsRescueDisableMag(void)
{
return true;
}
#endif
#endif // USE_GPS_RESCUE
#endif // USE_WING

View file

@ -0,0 +1,41 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include <stdbool.h>
#include "common/axis.h"
#include "pg/gps_rescue.h"
#define TASK_GPS_RESCUE_RATE_HZ 100 // in sync with altitude task rate
extern float gpsRescueAngle[RP_AXIS_COUNT]; // NOTE: ANGLES ARE IN CENTIDEGREES
void gpsRescueInit(void);
void gpsRescueUpdate(void);
float gpsRescueGetYawRate(void);
bool gpsRescueIsConfigured(void);
bool gpsRescueIsAvailable(void);
bool gpsRescueIsDisabled(void);
bool gpsRescueDisableMag(void);
float gpsRescueGetImuYawCogGain(void);
#endif // USE_WING

View file

@ -570,7 +570,7 @@ STATIC_UNIT_TESTED FAST_CODE_NOINLINE float pidLevel(int axis, const pidProfile_
#ifdef USE_GPS_RESCUE
angleTarget += gpsRescueAngle[axis] / 100.0f; // Angle is in centidegrees, stepped on roll at 10Hz but not on pitch
#endif
#ifdef USE_POSITION_HOLD
#if defined(USE_POSITION_HOLD) && !defined(USE_WING)
if (FLIGHT_MODE(POS_HOLD_MODE)) {
angleFeedforward = 0.0f; // otherwise the lag of the PT3 carries recent stick inputs into the hold
if (isAutopilotInControl()) {
@ -1127,7 +1127,7 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
|| FLIGHT_MODE(ALT_HOLD_MODE) // todo - check if this is needed
#endif
#ifdef USE_POSITION_HOLD
|| FLIGHT_MODE(POS_HOLD_MODE)
|| FLIGHT_MODE(POS_HOLD_MODE)
#endif
;
levelMode_e levelMode;

View file

@ -17,17 +17,5 @@
#pragma once
// #include "pg/pos_hold.h"
#ifdef USE_POSITION_HOLD
#include "common/time.h"
#include "io/gps.h"
#define POSHOLD_TASK_RATE_HZ 100 // hz
void posHoldInit(void);
void updatePosHold(timeUs_t currentTimeUs);
bool posHoldFailure(void);
#endif
#include "flight/pos_hold_multirotor.h"
#include "flight/pos_hold_wing.h"

View file

@ -17,6 +17,8 @@
#include "platform.h"
#ifndef USE_WING
#ifdef USE_POSITION_HOLD
#include "math.h"
@ -55,7 +57,7 @@ void posHoldInit(void)
void posHoldCheckSticks(void)
{
// if failsafe is active, eg landing mode, don't update the original start point
// if failsafe is active, eg landing mode, don't update the original start point
if (!failsafeIsActive() && posHold.useStickAdjustment) {
const bool sticksDeflected = (getRcDeflectionAbs(FD_ROLL) > posHold.deadband) || (getRcDeflectionAbs(FD_PITCH) > posHold.deadband);
setSticksActiveStatus(sticksDeflected);
@ -65,20 +67,20 @@ void posHoldCheckSticks(void)
bool sensorsOk(void)
{
if (!STATE(GPS_FIX)) {
return false;
return false;
}
if (
#ifdef USE_MAG
!compassIsHealthy() &&
#endif
(!posHoldConfig()->pos_hold_without_mag || !canUseGPSHeading)) {
return false;
return false;
}
return true;
}
void updatePosHold(timeUs_t currentTimeUs) {
UNUSED(currentTimeUs);
UNUSED(currentTimeUs);
if (FLIGHT_MODE(POS_HOLD_MODE)) {
if (!posHold.isEnabled) {
resetPositionControl(&gpsSol.llh, POSHOLD_TASK_RATE_HZ); // sets target location to current location
@ -104,3 +106,5 @@ bool posHoldFailure(void) {
}
#endif // USE_POS_HOLD
#endif // !USE_WING

View file

@ -0,0 +1,37 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
// #include "pg/pos_hold.h"
#ifdef USE_POSITION_HOLD
#include "common/time.h"
#include "io/gps.h"
#define POSHOLD_TASK_RATE_HZ 100 // hz
void posHoldInit(void);
void updatePosHold(timeUs_t currentTimeUs);
bool posHoldFailure(void);
#endif // USE_POSITION_HOLD
#endif // !USE_WING

View file

@ -0,0 +1,57 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_WING
#ifdef USE_POSITION_HOLD
#include "math.h"
#include "build/debug.h"
#include "common/maths.h"
#include "config/config.h"
#include "fc/core.h"
#include "fc/runtime_config.h"
#include "fc/rc.h"
#include "flight/autopilot.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/position.h"
#include "rx/rx.h"
#include "sensors/compass.h"
#include "pg/pos_hold.h"
#include "pos_hold.h"
void posHoldInit(void)
{
}
void updatePosHold(timeUs_t currentTimeUs) {
UNUSED(currentTimeUs);
}
bool posHoldFailure(void) {
// used only to display warning in OSD if requested but failing
return true;
}
#endif // USE_POS_HOLD
#endif // USE_WING

View file

@ -0,0 +1,37 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
// #include "pg/pos_hold.h"
#ifdef USE_POSITION_HOLD
#include "common/time.h"
#include "io/gps.h"
#define POSHOLD_TASK_RATE_HZ 100 // hz
void posHoldInit(void);
void updatePosHold(timeUs_t currentTimeUs);
bool posHoldFailure(void);
#endif
#endif // USE_WING

View file

@ -1533,6 +1533,7 @@ case MSP_NAME:
break;
#ifdef USE_GPS_RESCUE
#ifndef USE_WING
case MSP_GPS_RESCUE:
sbufWriteU16(dst, gpsRescueConfig()->maxRescueAngle);
sbufWriteU16(dst, gpsRescueConfig()->returnAltitudeM);
@ -1565,6 +1566,7 @@ case MSP_NAME:
sbufWriteU16(dst, gpsRescueConfig()->velD);
sbufWriteU16(dst, gpsRescueConfig()->yawP);
break;
#endif // !USE_WING
#endif
#endif
@ -1802,7 +1804,7 @@ case MSP_NAME:
case MSP_RC_DEADBAND:
sbufWriteU8(dst, rcControlsConfig()->deadband);
sbufWriteU8(dst, rcControlsConfig()->yaw_deadband);
#ifdef USE_POSITION_HOLD
#if defined(USE_POSITION_HOLD) && !defined(USE_WING)
sbufWriteU8(dst, posHoldConfig()->pos_hold_deadband);
#else
sbufWriteU8(dst, 0);
@ -2879,6 +2881,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
#ifdef USE_GPS
#ifdef USE_GPS_RESCUE
#ifndef USE_WING
case MSP_SET_GPS_RESCUE:
gpsRescueConfigMutable()->maxRescueAngle = sbufReadU16(src);
gpsRescueConfigMutable()->returnAltitudeM = sbufReadU16(src);
@ -2916,6 +2919,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
gpsRescueConfigMutable()->velD = sbufReadU16(src);
gpsRescueConfigMutable()->yawP = sbufReadU16(src);
break;
#endif // !USE_WING
#endif
#endif
@ -2971,7 +2975,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
case MSP_SET_RC_DEADBAND:
rcControlsConfigMutable()->deadband = sbufReadU8(src);
rcControlsConfigMutable()->yaw_deadband = sbufReadU8(src);
#ifdef USE_POSITION_HOLD
#if defined(USE_POSITION_HOLD) && !defined(USE_WING)
posHoldConfigMutable()->pos_hold_deadband = sbufReadU8(src);
#else
sbufReadU8(src);

View file

@ -21,13 +21,5 @@
#pragma once
#include <stdint.h>
#include "pg/pg.h"
typedef struct altHoldConfig_s {
uint8_t alt_hold_adjust_rate;
uint8_t alt_hold_deadband;
} altHoldConfig_t;
PG_DECLARE(altHoldConfig_t, altHoldConfig);
#include "pg/alt_hold_multirotor.h"
#include "pg/alt_hold_wing.h"

View file

@ -21,6 +21,8 @@
#include "platform.h"
#ifndef USE_WING
#ifdef USE_ALTITUDE_HOLD
#include "flight/alt_hold.h"
@ -37,3 +39,5 @@ PG_RESET_TEMPLATE(altHoldConfig_t, altHoldConfig,
.alt_hold_deadband = 20, // throttle deadband in percent of stick travel
);
#endif
#endif // USE_WING

View file

@ -0,0 +1,37 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct altHoldConfig_s {
uint8_t alt_hold_adjust_rate;
uint8_t alt_hold_deadband;
} altHoldConfig_t;
PG_DECLARE(altHoldConfig_t, altHoldConfig);
#endif // !USE_WING

View file

@ -0,0 +1,41 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_WING
#ifdef USE_ALTITUDE_HOLD
#include "flight/alt_hold.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "alt_hold.h"
PG_REGISTER_WITH_RESET_TEMPLATE(altHoldConfig_t, altHoldConfig, PG_ALTHOLD_CONFIG, 4);
PG_RESET_TEMPLATE(altHoldConfig_t, altHoldConfig,
);
#endif
#endif // USE_WING

View file

@ -0,0 +1,36 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct altHoldConfig_s {
uint8_t dummy;
} altHoldConfig_t;
PG_DECLARE(altHoldConfig_t, altHoldConfig);
#endif // USE_WING

View file

@ -21,26 +21,5 @@
#pragma once
#include <stdint.h>
#include "pg/pg.h"
typedef struct apConfig_s {
uint8_t landing_altitude_m; // altitude below which landing behaviours can change, metres
uint16_t hover_throttle; // value used at the start of a rescue or position hold
uint16_t throttle_min;
uint16_t throttle_max;
uint8_t altitude_P;
uint8_t altitude_I;
uint8_t altitude_D;
uint8_t altitude_F;
uint8_t position_P;
uint8_t position_I;
uint8_t position_D;
uint8_t position_A;
uint8_t position_cutoff;
uint8_t max_angle;
} apConfig_t;
PG_DECLARE(apConfig_t, apConfig);
#include "pg/autopilot_multirotor.h"
#include "pg/autopilot_wing.h"

View file

@ -21,6 +21,8 @@
#include "platform.h"
#ifndef USE_WING
#include "flight/autopilot.h"
#include "pg/pg.h"
@ -46,3 +48,5 @@ PG_RESET_TEMPLATE(apConfig_t, apConfig,
.position_cutoff = 80,
.max_angle = 50,
);
#endif // !USE_WING

View file

@ -0,0 +1,49 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct apConfig_s {
uint8_t landing_altitude_m; // altitude below which landing behaviours can change, metres
uint16_t hover_throttle; // value used at the start of a rescue or position hold
uint16_t throttle_min;
uint16_t throttle_max;
uint8_t altitude_P;
uint8_t altitude_I;
uint8_t altitude_D;
uint8_t altitude_F;
uint8_t position_P;
uint8_t position_I;
uint8_t position_D;
uint8_t position_A;
uint8_t position_cutoff;
uint8_t max_angle;
} apConfig_t;
PG_DECLARE(apConfig_t, apConfig);
#endif // !USE_WING

View file

@ -0,0 +1,38 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_WING
#include "flight/autopilot.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "autopilot.h"
PG_REGISTER_WITH_RESET_TEMPLATE(apConfig_t, apConfig, PG_AUTOPILOT, 2);
PG_RESET_TEMPLATE(apConfig_t, apConfig,
);
#endif // USE_WING

View file

@ -0,0 +1,36 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct apConfig_s {
uint8_t dummy;
} apConfig_t;
PG_DECLARE(apConfig_t, apConfig);
#endif // USE_WING

View file

@ -1,50 +1,21 @@
/*
* This file is part of Cleanflight and Betaflight.
* This file is part of Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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.
* Betaflight 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 and Betaflight are distributed in the hope that they
* 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.
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
* along with Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
#include "pg/pg.h"
typedef struct gpsRescue_s {
uint16_t maxRescueAngle; // degrees
uint16_t returnAltitudeM; // meters
uint16_t descentDistanceM; // meters
uint16_t groundSpeedCmS; // centimeters per second
uint8_t yawP;
uint8_t minSats;
uint8_t velP, velI, velD;
uint16_t minStartDistM; // meters
uint8_t sanityChecks;
uint8_t allowArmingWithoutFix;
uint8_t useMag;
uint8_t altitudeMode;
uint16_t ascendRate;
uint16_t descendRate;
uint16_t initialClimbM; // meters
uint8_t rollMix;
uint8_t disarmThreshold;
uint8_t pitchCutoffHz;
uint8_t imuYawGain;
} gpsRescueConfig_t;
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);
#include "pg/gps_rescue_multirotor.h"
#include "pg/gps_rescue_wing.h"

View file

@ -20,6 +20,8 @@
#include "platform.h"
#ifndef USE_WING
#ifdef USE_GPS_RESCUE
#include "flight/gps_rescue.h"
@ -62,3 +64,5 @@ PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig,
);
#endif // USE_GPS_RESCUE
#endif // !USE_WING

View file

@ -0,0 +1,54 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct gpsRescue_s {
uint16_t maxRescueAngle; // degrees
uint16_t returnAltitudeM; // meters
uint16_t descentDistanceM; // meters
uint16_t groundSpeedCmS; // centimeters per second
uint8_t yawP;
uint8_t minSats;
uint8_t velP, velI, velD;
uint16_t minStartDistM; // meters
uint8_t sanityChecks;
uint8_t allowArmingWithoutFix;
uint8_t useMag;
uint8_t altitudeMode;
uint16_t ascendRate;
uint16_t descendRate;
uint16_t initialClimbM; // meters
uint8_t rollMix;
uint8_t disarmThreshold;
uint8_t pitchCutoffHz;
uint8_t imuYawGain;
} gpsRescueConfig_t;
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);
#endif // !USE_WING

View file

@ -0,0 +1,40 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_WING
#ifdef USE_GPS_RESCUE
#include "flight/gps_rescue.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "gps_rescue.h"
PG_REGISTER_WITH_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 7);
PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig,
.allowArmingWithoutFix = false,
.minSats = 8,
);
#endif // USE_GPS_RESCUE
#endif // USE_WING

View file

@ -0,0 +1,33 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* Betaflight 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct gpsRescue_s {
uint8_t allowArmingWithoutFix;
uint8_t minSats;
} gpsRescueConfig_t;
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);
#endif // USE_WING

View file

@ -21,13 +21,5 @@
#pragma once
#include <stdint.h>
#include "pg/pg.h"
typedef struct posHoldConfig_s {
bool pos_hold_without_mag;
uint8_t pos_hold_deadband;
} posHoldConfig_t;
PG_DECLARE(posHoldConfig_t, posHoldConfig);
#include "pg/pos_hold_multirotor.h"
#include "pg/pos_hold_wing.h"

View file

@ -21,6 +21,8 @@
#include "platform.h"
#ifndef USE_WING
#ifdef USE_POSITION_HOLD
#include "flight/pos_hold.h"
@ -37,3 +39,5 @@ PG_RESET_TEMPLATE(posHoldConfig_t, posHoldConfig,
.pos_hold_deadband = 5, // deadband in percent of stick travel for roll and pitch. Must be non-zero, and exceeded, for target location to be changed with sticks
);
#endif
#endif // !USE_WING

View file

@ -0,0 +1,37 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifndef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct posHoldConfig_s {
bool pos_hold_without_mag;
uint8_t pos_hold_deadband;
} posHoldConfig_t;
PG_DECLARE(posHoldConfig_t, posHoldConfig);
#endif // !USE_WING

View file

@ -0,0 +1,41 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#ifdef USE_WING
#ifdef USE_POSITION_HOLD
#include "flight/pos_hold.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pos_hold.h"
PG_REGISTER_WITH_RESET_TEMPLATE(posHoldConfig_t, posHoldConfig, PG_POSHOLD_CONFIG, 0);
PG_RESET_TEMPLATE(posHoldConfig_t, posHoldConfig,
);
#endif
#endif // USE_WING

View file

@ -0,0 +1,36 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef USE_WING
#include <stdint.h>
#include "pg/pg.h"
typedef struct posHoldConfig_s {
uint8_t dummy;
} posHoldConfig_t;
PG_DECLARE(posHoldConfig_t, posHoldConfig);
#endif // !USE_WING

View file

@ -37,8 +37,8 @@ alignsensor_unittest_SRC := \
$(USER_DIR)/common/vector.c
althold_unittest_SRC := \
$(USER_DIR)/flight/alt_hold.c \
$(USER_DIR)/flight/autopilot.c \
$(USER_DIR)/flight/alt_hold_multirotor.c \
$(USER_DIR)/flight/autopilot_multirotor.c \
$(USER_DIR)/common/maths.c \
$(USER_DIR)/common/vector.c \
$(USER_DIR)/common/filter.c \
@ -56,8 +56,8 @@ arming_prevention_unittest_SRC := \
$(USER_DIR)/fc/rc_controls.c \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/fc/runtime_config.c \
$(USER_DIR)/flight/autopilot.c \
$(USER_DIR)/flight/gps_rescue.c
$(USER_DIR)/flight/autopilot_multirotor.c \
$(USER_DIR)/flight/gps_rescue_multirotor.c
arming_prevention_unittest_DEFINES := \
USE_GPS_RESCUE=