mirror of https://github.com/ArduPilot/ardupilot
150 lines
5.7 KiB
C++
150 lines
5.7 KiB
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
#include "Copter.h"
|
|
|
|
/*
|
|
* control_loiter.pde - init and run calls for loiter flight mode
|
|
*/
|
|
|
|
// loiter_init - initialise loiter controller
|
|
bool Copter::loiter_init(bool ignore_checks)
|
|
{
|
|
if (position_ok() || ignore_checks) {
|
|
|
|
// set target to current position
|
|
wp_nav.init_loiter_target();
|
|
|
|
// initialize vertical speed and accelerationj
|
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
|
pos_control.set_accel_z(g.pilot_accel_z);
|
|
|
|
// initialise position and desired velocity
|
|
pos_control.set_alt_target(inertial_nav.get_altitude());
|
|
pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
|
|
|
|
return true;
|
|
}else{
|
|
return false;
|
|
}
|
|
}
|
|
|
|
// loiter_run - runs the loiter controller
|
|
// should be called at 100hz or more
|
|
void Copter::loiter_run()
|
|
{
|
|
LoiterModeState loiter_state;
|
|
float target_yaw_rate = 0.0f;
|
|
float target_climb_rate = 0.0f;
|
|
float takeoff_climb_rate = 0.0f;
|
|
|
|
// process pilot inputs unless we are in radio failsafe
|
|
if (!failsafe.radio) {
|
|
// apply SIMPLE mode transform to pilot inputs
|
|
update_simple_mode();
|
|
|
|
// process pilot's roll and pitch input
|
|
wp_nav.set_pilot_desired_acceleration(channel_roll->control_in, channel_pitch->control_in);
|
|
|
|
// get pilot's desired yaw rate
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
|
|
|
// get pilot desired climb rate
|
|
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in);
|
|
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
|
} else {
|
|
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
|
|
wp_nav.clear_pilot_desired_acceleration();
|
|
}
|
|
|
|
// relax loiter target if we might be landed
|
|
if (ap.land_complete_maybe) {
|
|
wp_nav.loiter_soften_for_landing();
|
|
}
|
|
|
|
// Loiter State Machine Determination
|
|
if(!ap.auto_armed || !motors.get_interlock()) {
|
|
loiter_state = Loiter_Disarmed;
|
|
} else if (takeoff_state.running || (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()))){
|
|
loiter_state = Loiter_Takeoff;
|
|
} else if (ap.land_complete){
|
|
loiter_state = Loiter_Landed;
|
|
} else {
|
|
loiter_state = Loiter_Flying;
|
|
}
|
|
|
|
// Loiter State Machine
|
|
switch (loiter_state) {
|
|
|
|
case Loiter_Disarmed:
|
|
|
|
wp_nav.init_loiter_target();
|
|
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
|
// call attitude controller
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
|
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
|
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
|
#endif // HELI_FRAME
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
|
break;
|
|
|
|
case Loiter_Takeoff:
|
|
|
|
if (!takeoff_state.running) {
|
|
takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
|
// indicate we are taking off
|
|
set_land_complete(false);
|
|
// clear i term when we're taking off
|
|
set_throttle_takeoff();
|
|
}
|
|
|
|
// get takeoff adjusted pilot and takeoff climb rates
|
|
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
|
|
|
|
// run loiter controller
|
|
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
|
|
|
// call attitude controller
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
|
|
|
// update altitude target and call position controller
|
|
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
|
pos_control.add_takeoff_climb_rate(takeoff_climb_rate, G_Dt);
|
|
pos_control.update_z_controller();
|
|
break;
|
|
|
|
case Loiter_Landed:
|
|
|
|
wp_nav.init_loiter_target();
|
|
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
|
// call attitude controller
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
|
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
|
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
|
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
|
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
|
#endif
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
|
break;
|
|
|
|
case Loiter_Flying:
|
|
|
|
// run loiter controller
|
|
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
|
|
|
// call attitude controller
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
|
|
|
// run altitude controller
|
|
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
|
// if sonar is ok, use surface tracking
|
|
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
|
}
|
|
|
|
// update altitude target and call position controller
|
|
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
|
pos_control.update_z_controller();
|
|
break;
|
|
}
|
|
}
|