mirror of https://github.com/ArduPilot/ardupilot
Sub: fix missing _dz in get_pilot_desired_yaw_rate()
This commit is contained in:
parent
65576b7895
commit
f222b8bb59
|
@ -123,7 +123,7 @@ void Sub::auto_wp_run()
|
|||
float target_yaw_rate = 0;
|
||||
if (!failsafe.pilot_input) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
|
@ -313,7 +313,7 @@ void Sub::auto_loiter_run()
|
|||
// accept pilot input of yaw
|
||||
float target_yaw_rate = 0;
|
||||
if (!failsafe.pilot_input) {
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
}
|
||||
|
||||
// set motors to full range
|
||||
|
|
|
@ -48,7 +48,7 @@ void Sub::circle_run()
|
|||
|
||||
// process pilot inputs
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
circle_pilot_yaw_override = true;
|
||||
}
|
||||
|
|
|
@ -296,7 +296,7 @@ void Sub::guided_pos_control_run()
|
|||
float target_yaw_rate = 0;
|
||||
if (!failsafe.pilot_input) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
|
@ -349,7 +349,7 @@ void Sub::guided_vel_control_run()
|
|||
float target_yaw_rate = 0;
|
||||
if (!failsafe.pilot_input) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
|
@ -407,7 +407,7 @@ void Sub::guided_posvel_control_run()
|
|||
|
||||
if (!failsafe.pilot_input) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
|
|
|
@ -43,7 +43,7 @@ void Sub::surface_run()
|
|||
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_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->norm_input()) * 100;
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()) * 100;
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
||||
|
|
Loading…
Reference in New Issue