mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merged theothercliff/OP-1154_Cruise_Control_automatically_increase_copter_throttle_per_1/cos(bank_angle)
Changed pid banks to use flight mode switch position instead of FlightStatus.FlightMode
This commit is contained in:
parent
f096d01e3c
commit
2b32c5ebc3
@ -102,7 +102,7 @@ bool lowThrottleZeroAxis[MAX_AXES];
|
||||
float vbar_decay = 0.991f;
|
||||
struct pid pids[PID_MAX];
|
||||
|
||||
int flight_mode = -1;
|
||||
int cur_flight_mode = -1;
|
||||
|
||||
static uint8_t rattitude_anti_windup;
|
||||
static float cruise_control_min_throttle;
|
||||
@ -235,9 +235,11 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
#ifdef DIAG_RATEDESIRED
|
||||
RateDesiredGet(&rateDesired);
|
||||
#endif
|
||||
uint8_t flight_mode_switch_position;
|
||||
ManualControlCommandFlightModeSwitchPositionGet(&flight_mode_switch_position);
|
||||
|
||||
if (flight_mode != flightStatus.FlightMode) {
|
||||
flight_mode = flightStatus.FlightMode;
|
||||
if (cur_flight_mode != flight_mode_switch_position) {
|
||||
cur_flight_mode = flight_mode_switch_position;
|
||||
SettingsBankUpdatedCb(NULL);
|
||||
}
|
||||
|
||||
@ -604,8 +606,6 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// to maintain same altitdue with changing bank angle
|
||||
// but without manually adjusting throttle
|
||||
// do it here and all the various flight modes (e.g. Altitude Hold) can use it
|
||||
uint8_t flight_mode_switch_position;
|
||||
ManualControlCommandFlightModeSwitchPositionGet(&flight_mode_switch_position);
|
||||
if (flight_mode_switch_position < NUM_FMS_POSITIONS
|
||||
&& cruise_control_flight_mode_switch_pos_enable[flight_mode_switch_position] != (uint8_t) 0
|
||||
&& cruise_control_max_power_factor > 0.0001f) {
|
||||
@ -759,11 +759,11 @@ static void SettingsBankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
|
||||
StabilizationBankGet(&oldBank);
|
||||
|
||||
if (flight_mode < 0) {
|
||||
if (cur_flight_mode < 0 || cur_flight_mode >= NUM_FMS_POSITIONS) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (cast_struct_to_array(settings.FlightModeMap, settings.FlightModeMap.Stabilized1)[flight_mode]) {
|
||||
switch (settings.FlightModeMap[cur_flight_mode]) {
|
||||
case 0:
|
||||
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *)&bank);
|
||||
break;
|
||||
@ -928,7 +928,7 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
vbar_decay = expf(-fakeDt / settings.VbarTau);
|
||||
|
||||
// force flight mode update
|
||||
flight_mode = -1;
|
||||
cur_flight_mode = -1;
|
||||
|
||||
// Rattitude flight mode anti-windup factor
|
||||
rattitude_anti_windup = settings.RattitudeAntiWindup;
|
||||
|
@ -3,11 +3,11 @@
|
||||
<object name="StabilizationSettings" singleinstance="true" settings="true" category="Control">
|
||||
<description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
|
||||
|
||||
<!-- Note: The number of elements here must match the number of available flight modes -->
|
||||
<field name="FlightModeMap" units="" type="enum"
|
||||
options="Bank1,Bank2,Bank3"
|
||||
elementnames="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,AltitudeVario,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI"
|
||||
defaultvalue="Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1"/>
|
||||
<!-- Note: The number of elements here must match the number of available flight mode switch positions -->
|
||||
<field name="FlightModeMap" units="" type="enum"
|
||||
options="Bank1,Bank2,Bank3"
|
||||
elements="6"
|
||||
defaultvalue="Bank1,Bank1,Bank1,Bank1,Bank1,Bank1"/>
|
||||
|
||||
<field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
|
||||
<field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user