// guided_takeoff_run - takeoff in guided mode // called by guided_run at 100hz or more void Copter::guided_takeoff_run() { // if not auto armed or motors not enabled set throttle to zero and exit immediately if (!motors.armed() || !ap.auto_armed || !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(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 return; } // process pilot's yaw input float target_yaw_rate = 0; if (!failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); } // set motors to full range motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // run waypoint controller failsafe_terrain_set_status(wp_nav.update_wpnav()); // call z-axis position controller (wpnav should have already updated it's alt target) pos_control.update_z_controller(); // call attitude controller auto_takeoff_attitude_run(target_yaw_rate); }
void Copter::Mode::auto_takeoff_run() { // if not armed set throttle to zero and exit immediately if (!motors->armed() || !ap.auto_armed) { make_safe_spool_down(); wp_nav->shift_wp_origin_to_current_pos(); return; } // process pilot's yaw input float target_yaw_rate = 0; if (!copter.failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); } // aircraft stays in landed state until rotor speed runup has finished if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { set_land_complete(false); } else { wp_nav->shift_wp_origin_to_current_pos(); } // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // run waypoint controller copter.failsafe_terrain_set_status(wp_nav->update_wpnav()); // call z-axis position controller (wpnav should have already updated it's alt target) copter.pos_control->update_z_controller(); // call attitude controller auto_takeoff_attitude_run(target_yaw_rate); }
void Copter::Mode::auto_takeoff_run() { // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) { // initialise wpnav targets wp_nav->shift_wp_origin_to_current_pos(); zero_throttle_and_relax_ac(); // clear i term when we're taking off set_throttle_takeoff(); return; } // process pilot's yaw input float target_yaw_rate = 0; if (!copter.failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); } #if FRAME_CONFIG == HELI_FRAME // helicopters stay in landed state until rotor speed runup has finished if (motors->rotor_runup_complete()) { set_land_complete(false); } else { // initialise wpnav targets wp_nav->shift_wp_origin_to_current_pos(); } #else set_land_complete(false); #endif // set motors to full range motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // run waypoint controller copter.failsafe_terrain_set_status(wp_nav->update_wpnav()); // call z-axis position controller (wpnav should have already updated it's alt target) copter.pos_control->update_z_controller(); // call attitude controller auto_takeoff_attitude_run(target_yaw_rate); }