mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: guided takeoff supports autoyaw
allows both pilot controlled and externally controlled yaw control
This commit is contained in:
parent
c23b7fdbd7
commit
944920610f
@ -111,6 +111,9 @@ void Mode::auto_takeoff_run()
|
|||||||
if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) {
|
if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) {
|
||||||
// get pilot's desired yaw rate
|
// get pilot's desired yaw rate
|
||||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
||||||
|
if (!is_zero(target_yaw_rate)) {
|
||||||
|
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// aircraft stays in landed state until rotor speed runup has finished
|
// aircraft stays in landed state until rotor speed runup has finished
|
||||||
@ -153,8 +156,17 @@ void Mode::auto_takeoff_run()
|
|||||||
// run the vertical position controller and set output throttle
|
// run the vertical position controller and set output throttle
|
||||||
copter.pos_control->update_z_controller();
|
copter.pos_control->update_z_controller();
|
||||||
|
|
||||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
// call attitude controller
|
||||||
attitude_control->input_thrust_vector_rate_heading(thrustvector, target_yaw_rate);
|
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)
|
void Mode::auto_takeoff_set_start_alt(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user