#define POSHOLD_SPEED_0 10 // speed below which it is always safe to switch to loiter
// 400hz loop update rate
#define POSHOLD_BRAKE_TIME_ESTIMATE_MAX (600*4) // max number of cycles the brake will be applied before we switch to loiter
#define POSHOLD_BRAKE_TO_LOITER_TIMER (150*4) // Number of cycles to transition from brake mode to loiter mode. Must be lower than POSHOLD_LOITER_STAB_TIMER
#define POSHOLD_WIND_COMP_START_TIMER (150*4) // Number of cycles to start wind compensation update after loiter is engaged
#define POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER (50*4) // Set it from 100 to 200, the number of centiseconds loiter and manual commands are mixed to make a smooth transition.
#define POSHOLD_SMOOTH_RATE_FACTOR 0.0125f // filter applied to pilot's roll/pitch input as it returns to center. A lower number will cause the roll/pitch to return to zero more slowly if the brake_rate is also low.
#define POSHOLD_WIND_COMP_TIMER_10HZ 40 // counter value used to reduce wind compensation to 10hz
#define LOOP_RATE_FACTOR 4 // used to adapt PosHold params to loop_rate
#define TC_WIND_COMP 0.0025f // Time constant for poshold_update_wind_comp_estimate()
// definitions that are independent of main loop rate
#define POSHOLD_STICK_RELEASE_SMOOTH_ANGLE 1800 // max angle required (in centi-degrees) after which the smooth stick release effect is applied
#define POSHOLD_WIND_COMP_ESTIMATE_SPEED_MAX 10 // wind compensation estimates will only run when velocity is at or below this speed in cm/s
// mission state enumeration
enumposhold_rp_mode{
POSHOLD_PILOT_OVERRIDE=0,// pilot is controlling this axis (i.e. roll or pitch)
POSHOLD_BRAKE,// this axis is braking towards zero
POSHOLD_BRAKE_READY_TO_LOITER,// this axis has completed braking and is ready to enter loiter mode (both modes must be this value before moving to next stage)
POSHOLD_BRAKE_TO_LOITER,// both vehicle's axis (roll and pitch) are transitioning from braking to loiter mode (braking and loiter controls are mixed)
POSHOLD_LOITER,// both vehicle axis are holding position
POSHOLD_CONTROLLER_TO_PILOT_OVERRIDE// pilot has input controls on this axis and this axis is transitioning to pilot override (other axis will transition to brake if no pilot input)
};
staticstruct{
poshold_rp_moderoll_mode:3;// roll mode: pilot override, brake or loiter
poshold_rp_modepitch_mode:3;// pitch mode: pilot override, brake or loiter
uint8_tbraking_time_updated_roll:1;// true once we have re-estimated the braking time. This is done once as the vehicle begins to flatten out after braking
uint8_tbraking_time_updated_pitch:1;// true once we have re-estimated the braking time. This is done once as the vehicle begins to flatten out after braking
uint8_tloiter_reset_I:1;// true the very first time PosHold enters loiter, thereafter we trust the i terms loiter has
// pilot input related variables
floatpilot_roll;// pilot requested roll angle (filtered to slow returns to zero)
floatpilot_pitch;// pilot requested roll angle (filtered to slow returns to zero)
// braking related variables
floatbrake_gain;// gain used during conversion of vehicle's velocity to lean angle during braking (calculated from brake_rate)
int16_tbrake_roll;// target roll angle during braking periods
int16_tbrake_pitch;// target pitch angle during braking periods
int16_tbrake_timeout_roll;// number of cycles allowed for the braking to complete, this timeout will be updated at half-braking
int16_tbrake_timeout_pitch;// number of cycles allowed for the braking to complete, this timeout will be updated at half-braking
int16_tbrake_angle_max_roll;// maximum lean angle achieved during braking. Used to determine when the vehicle has begun to flatten out so that we can re-estimate the braking time
int16_tbrake_angle_max_pitch;// maximum lean angle achieved during braking Used to determine when the vehicle has begun to flatten out so that we can re-estimate the braking time
int16_tbrake_to_loiter_timer;// cycles to mix brake and loiter controls in POSHOLD_BRAKE_TO_LOITER
// loiter related variables
int16_tcontroller_to_pilot_timer_roll;// cycles to mix controller and pilot controls in POSHOLD_CONTROLLER_TO_PILOT
int16_tcontroller_to_pilot_timer_pitch;// cycles to mix controller and pilot controls in POSHOLD_CONTROLLER_TO_PILOT
int16_tcontroller_final_roll;// final roll angle from controller as we exit brake or loiter mode (used for mixing with pilot input)
int16_tcontroller_final_pitch;// final pitch angle from controller as we exit brake or loiter mode (used for mixing with pilot input)
// wind compensation related variables
Vector2fwind_comp_ef;// wind compensation in earth frame, filtered lean angles from position controller
int16_twind_comp_roll;// roll angle to compensate for wind
int16_twind_comp_pitch;// pitch angle to compensate for wind
uint16_twind_comp_start_timer;// counter to delay start of wind compensation for a short time after loiter is engaged
int8_twind_comp_timer;// counter to reduce wind comp roll/pitch lean angle calcs to 10hz
// final output
int16_troll;// final roll angle sent to attitude controller
int16_tpitch;// final pitch angle sent to attitude controller
// only init here as we can switch to PosHold in flight with a velocity <> 0 that will be used as _last_vel in PosControl and never updated again as we inhibit Reset_I
wp_nav.init_loiter_target();
}else{
// if not landed start in pilot override to avoid hard twitch
poshold.roll_mode=POSHOLD_PILOT_OVERRIDE;
poshold.pitch_mode=POSHOLD_PILOT_OVERRIDE;
}
// loiter's I terms should be reset the first time only
poshold.loiter_reset_I=true;
// initialise wind_comp each time PosHold is switched on
poshold.wind_comp_ef.zero();
poshold.wind_comp_roll=0;
poshold.wind_comp_pitch=0;
poshold.wind_comp_timer=0;
returntrue;
}
// poshold_run - runs the PosHold controller
// should be called at 100hz or more
voidCopter::poshold_run()
{
floattarget_roll,target_pitch;// pilot's roll and pitch angle inputs
floattarget_yaw_rate=0;// pilot desired yaw rate in centi-degrees/sec
floattarget_climb_rate=0;// pilot desired climb rate in centimeters/sec
// braking angle has started decreasing so re-estimate braking time
poshold.brake_timeout_roll=1+(uint16_t)(LOOP_RATE_FACTOR*15L*(int32_t)(abs(poshold.brake_roll))/(10L*(int32_t)g.poshold_brake_rate));// the 1.2 (12/10) factor has to be tuned in flight, here it means 120% of the "normal" time.
poshold.braking_time_updated_roll=true;
}
}
// if velocity is very low reduce braking time to 0.5seconds
// braking angle has started decreasing so re-estimate braking time
poshold.brake_timeout_pitch=1+(uint16_t)(LOOP_RATE_FACTOR*15L*(int32_t)(abs(poshold.brake_pitch))/(10L*(int32_t)g.poshold_brake_rate));// the 1.2 (12/10) factor has to be tuned in flight, here it means 120% of the "normal" time.
poshold.braking_time_updated_pitch=true;
}
}
// if velocity is very low reduce braking time to 0.5seconds
wp_nav.init_loiter_target(inertial_nav.get_position(),poshold.loiter_reset_I);// (false) to avoid I_term reset. In original code, velocity(0,0,0) was used instead of current velocity: wp_nav.init_loiter_target(inertial_nav.get_position(), Vector3f(0,0,0));
// at this stage, we are going to run update_loiter that will reset I_term once. From now, we ensure next time that we will enter loiter and update it, I_term won't be reset anymore
poshold.loiter_reset_I=false;
// set delay to start of wind compensation estimate updates
// initialise pilot_roll to 0, wind_comp will be updated to compensate and poshold_update_pilot_lean_angle function shall not smooth this transition at next iteration. so 0 is the right value
poshold.pilot_roll=0;
// store final controller output for mixing with pilot input
poshold.controller_final_roll=poshold.roll;
}
// poshold_pitch_controller_to_pilot_override - initialises transition from a controller submode (brake or loiter) to a pilot override on roll axis
// initialise pilot_pitch to 0, wind_comp will be updated to compensate and poshold_update_pilot_lean_angle function shall not smooth this transition at next iteration. so 0 is the right value
poshold.pilot_pitch=0;
// store final loiter outputs for mixing with pilot input