mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Copter: Two processes in one
This commit is contained in:
parent
e71baf4a6a
commit
5ce731fa00
@ -261,11 +261,7 @@ void ModeSystemId::run()
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
||||
|
||||
// output pilot's throttle
|
||||
if (copter.is_tradheli()) {
|
||||
attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
|
||||
} else {
|
||||
attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt);
|
||||
}
|
||||
attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt);
|
||||
|
||||
if (log_subsample <= 0) {
|
||||
log_data();
|
||||
|
Loading…
Reference in New Issue
Block a user