Copter: Update use of input_vel_accel_z

This commit is contained in:
Leonard Hall 2022-12-15 22:14:58 +10:30 committed by Randy Mackay
parent 87c684b5ee
commit 502989d5f3
1 changed files with 3 additions and 3 deletions

View File

@ -736,7 +736,7 @@ void ModeGuided::accel_control_run()
auto_yaw.set_mode(AutoYaw::Mode::HOLD); auto_yaw.set_mode(AutoYaw::Mode::HOLD);
} }
pos_control->input_vel_accel_xy(guided_vel_target_cms.xy(), guided_accel_target_cmss.xy(), false); pos_control->input_vel_accel_xy(guided_vel_target_cms.xy(), guided_accel_target_cmss.xy(), false);
pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false, false); pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false);
} else { } else {
// update position controller with new target // update position controller with new target
pos_control->input_accel_xy(guided_accel_target_cmss); pos_control->input_accel_xy(guided_accel_target_cmss);
@ -804,7 +804,7 @@ void ModeGuided::velaccel_control_run()
// set position errors to zero // set position errors to zero
pos_control->stop_pos_xy_stabilisation(); pos_control->stop_pos_xy_stabilisation();
} }
pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false, false); pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false);
// call velocity controller which includes z axis controller // call velocity controller which includes z axis controller
pos_control->update_xy_controller(); pos_control->update_xy_controller();
@ -834,7 +834,7 @@ void ModeGuided::pause_control_run()
// set the vertical velocity and acceleration targets to zero // set the vertical velocity and acceleration targets to zero
float vel_z = 0.0; float vel_z = 0.0;
pos_control->input_vel_accel_z(vel_z, 0.0, false, false); pos_control->input_vel_accel_z(vel_z, 0.0, false);
// call velocity controller which includes z axis controller // call velocity controller which includes z axis controller
pos_control->update_xy_controller(); pos_control->update_xy_controller();