|
|
|
@ -111,6 +111,9 @@ void Mode::auto_takeoff_run()
@@ -111,6 +111,9 @@ void Mode::auto_takeoff_run()
|
|
|
|
|
if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) { |
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); |
|
|
|
|
if (!is_zero(target_yaw_rate)) { |
|
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// aircraft stays in landed state until rotor speed runup has finished
|
|
|
|
@ -153,8 +156,17 @@ void Mode::auto_takeoff_run()
@@ -153,8 +156,17 @@ void Mode::auto_takeoff_run()
|
|
|
|
|
// run the vertical position controller and set output throttle
|
|
|
|
|
copter.pos_control->update_z_controller(); |
|
|
|
|
|
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_thrust_vector_rate_heading(thrustvector, target_yaw_rate); |
|
|
|
|
// call attitude controller
|
|
|
|
|
if (auto_yaw.mode() == AUTO_YAW_HOLD) { |
|
|
|
|
// roll & pitch from position controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_thrust_vector_rate_heading(thrustvector, target_yaw_rate); |
|
|
|
|
} else if (auto_yaw.mode() == AUTO_YAW_RATE) { |
|
|
|
|
// roll & pitch from position controller, yaw rate from mavlink command or mission item
|
|
|
|
|
attitude_control->input_thrust_vector_rate_heading(thrustvector, auto_yaw.rate_cds()); |
|
|
|
|
} else { |
|
|
|
|
// roll & pitch from position controller, yaw heading from GCS or auto_heading()
|
|
|
|
|
attitude_control->input_thrust_vector_heading(thrustvector, auto_yaw.yaw(), auto_yaw.rate_cds()); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Mode::auto_takeoff_set_start_alt(void) |
|
|
|
|