// land_nogps_run - runs the land controller // pilot controls roll and pitch angles // should be called at 100hz or more void Sub::land_nogps_run() { float target_roll = 0.0f, target_pitch = 0.0f; float target_yaw_rate = 0; // process pilot inputs if (!failsafe.radio) { if (g.land_repositioning) { // apply SIMPLE mode transform to pilot inputs update_simple_mode(); // get pilot desired lean angles get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); } // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately if(!ap.auto_armed || ap.at_surface || !motors.get_interlock()) { // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED // disarm when the landing detector says we've landed and throttle is at minimum if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { init_disarm_motors(); } #else // disarm when the landing detector says we've landed if (ap.at_surface) { set_mode(ALT_HOLD); } #endif return; } // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); // pause 4 seconds before beginning land descent float cmb_rate; if(land_pause && millis()-land_start_time < LAND_WITH_DELAY_MS) { cmb_rate = 0; } else { land_pause = false; cmb_rate = get_land_descent_speed(); } // record desired climb rate for logging desired_climb_rate = cmb_rate; // call position controller pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true); pos_control.update_z_controller(); }
// auto_land_run - lands in auto mode // called by auto_run at 100hz or more void Copter::auto_land_run() { int16_t roll_control = 0, pitch_control = 0; float target_yaw_rate = 0; // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately if(!ap.auto_armed || ap.land_complete) { #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 // Multirotors do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif // set target to current position wp_nav.init_loiter_target(); return; } // relax loiter targets if we might be landed if (ap.land_complete_maybe) { wp_nav.loiter_soften_for_landing(); } // process pilot's input if (!failsafe.radio) { if (g.land_repositioning) { // apply SIMPLE mode transform to pilot inputs update_simple_mode(); // process pilot's roll and pitch input roll_control = channel_roll->control_in; pitch_control = channel_pitch->control_in; } // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // process roll, pitch inputs wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control); // run loiter controller wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); // call z-axis position controller float cmb_rate = get_land_descent_speed(); pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true); pos_control.update_z_controller(); // record desired climb rate for logging desired_climb_rate = cmb_rate; // roll & pitch from waypoint controller, yaw rate from pilot attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate); }
// land_run - runs the land controller // horizontal position controlled with loiter controller // should be called at 100hz or more void Copter::land_gps_run() { int16_t roll_control = 0, pitch_control = 0; float target_yaw_rate = 0; // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) { #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 // Multirotors do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif wp_nav.init_loiter_target(); #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED // disarm when the landing detector says we've landed and throttle is at minimum if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { init_disarm_motors(); } #else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } #endif return; } // relax loiter target if we might be landed if (ap.land_complete_maybe) { wp_nav.loiter_soften_for_landing(); } // process pilot inputs if (!failsafe.radio) { if (g.land_repositioning) { // apply SIMPLE mode transform to pilot inputs update_simple_mode(); // process pilot's roll and pitch input roll_control = channel_roll->control_in; pitch_control = channel_pitch->control_in; } // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // process roll, pitch inputs wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control); // 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); // pause 4 seconds before beginning land descent float cmb_rate; if(land_pause && millis()-land_start_time < 4000) { cmb_rate = 0; } else { land_pause = false; cmb_rate = get_land_descent_speed(); } // record desired climb rate for logging desired_climb_rate = cmb_rate; // update altitude target and call position controller pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true); pos_control.update_z_controller(); }
// land_run - runs the land controller // horizontal position controlled with loiter controller // should be called at 100hz or more void Copter::land_gps_run() { int16_t roll_control = 0, pitch_control = 0; float target_yaw_rate = 0; // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately if (!motors.armed() || !ap.auto_armed || ap.land_complete || !motors.get_interlock()) { #if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.set_throttle_out(0,false,g.throttle_filt); #else motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif wp_nav.init_loiter_target(); #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED // disarm when the landing detector says we've landed and throttle is at minimum if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { init_disarm_motors(); } #else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } #endif return; } // relax loiter target if we might be landed if (ap.land_complete_maybe) { wp_nav.loiter_soften_for_landing(); } // process pilot inputs if (!failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT); // exit land if throttle is high if (!set_mode(LOITER)) { set_mode(ALT_HOLD); } } if (g.land_repositioning) { // apply SIMPLE mode transform to pilot inputs update_simple_mode(); // process pilot's roll and pitch input roll_control = channel_roll->control_in; pitch_control = channel_pitch->control_in; // record if pilot has overriden roll or pitch if (roll_control != 0 || pitch_control != 0) { ap.land_repo_active = true; } } // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // set motors to full range motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // process roll, pitch inputs wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control); #if PRECISION_LANDING == ENABLED // run precision landing if (!ap.land_repo_active) { wp_nav.shift_loiter_target(precland.get_target_shift(wp_nav.get_loiter_target())); } #endif // run loiter controller wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate); // pause 4 seconds before beginning land descent float cmb_rate; if(land_pause && millis()-land_start_time < 4000) { cmb_rate = 0; } else { land_pause = false; cmb_rate = get_land_descent_speed(); } // record desired climb rate for logging desired_climb_rate = cmb_rate; // update altitude target and call position controller pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true); pos_control.update_z_controller(); }
// land_nogps_run - runs the land controller // pilot controls roll and pitch angles // should be called at 100hz or more void Copter::land_nogps_run() { float target_roll = 0.0f, target_pitch = 0.0f; float target_yaw_rate = 0; // process pilot inputs if (!failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT); // exit land if throttle is high set_mode(ALT_HOLD); } if (g.land_repositioning) { // apply SIMPLE mode transform to pilot inputs update_simple_mode(); // get pilot desired lean angles get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); } // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately if (!motors.armed() || !ap.auto_armed || ap.land_complete || !motors.get_interlock()) { #if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); attitude_control.set_throttle_out(0,false,g.throttle_filt); #else motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED // disarm when the landing detector says we've landed and throttle is at minimum if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { init_disarm_motors(); } #else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } #endif return; } // set motors to full range motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); // pause 4 seconds before beginning land descent float cmb_rate; if(land_pause && millis()-land_start_time < LAND_WITH_DELAY_MS) { cmb_rate = 0; } else { land_pause = false; cmb_rate = get_land_descent_speed(); } // record desired climb rate for logging desired_climb_rate = cmb_rate; // call position controller pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true); pos_control.update_z_controller(); }
// rtl_returnhome_run - return home // called by rtl_run at 100hz or more void Copter::rtl_land_run() { int16_t roll_control = 0, pitch_control = 0; float target_yaw_rate = 0; // if not auto armed or landing completed or motor interlock not enabled set throttle to zero and exit immediately if (!motors.armed() || !ap.auto_armed || ap.land_complete || !motors.get_interlock()) { #if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.set_throttle_out(0,false,g.throttle_filt); #else motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif // set target to current position wp_nav.init_loiter_target(); #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED // disarm when the landing detector says we've landed and throttle is at minimum if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { init_disarm_motors(); } #else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } #endif // check if we've completed this stage of RTL rtl_state_complete = ap.land_complete; return; } // relax loiter target if we might be landed if (ap.land_complete_maybe) { wp_nav.loiter_soften_for_landing(); } // process pilot's input if (!failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT); // exit land if throttle is high if (!set_mode(LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) { set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE); } } if (g.land_repositioning) { // apply SIMPLE mode transform to pilot inputs update_simple_mode(); // process pilot's roll and pitch input roll_control = channel_roll->control_in; pitch_control = channel_pitch->control_in; } // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // set motors to full range motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // process pilot's roll and pitch input wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control); // run loiter controller wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); // call z-axis position controller float cmb_rate = get_land_descent_speed(); pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true); pos_control.update_z_controller(); // record desired climb rate for logging desired_climb_rate = cmb_rate; // roll & pitch from waypoint controller, yaw rate from pilot attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate); // check if we've completed this stage of RTL rtl_state_complete = ap.land_complete; }