mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AC_AttitudeControl: Support seperate roll and pitch limits
This commit is contained in:
parent
036b47ec56
commit
7f5d6662b3
@ -329,10 +329,10 @@ void AC_AttitudeControl_Multi::rate_controller_run()
|
|||||||
|
|
||||||
Vector3f gyro_latest = _ahrs.get_gyro_latest();
|
Vector3f gyro_latest = _ahrs.get_gyro_latest();
|
||||||
|
|
||||||
_motors.set_roll(get_rate_roll_pid().update_all(_rate_target_ang_vel.x, gyro_latest.x, _motors.limit.roll_pitch));
|
_motors.set_roll(get_rate_roll_pid().update_all(_rate_target_ang_vel.x, gyro_latest.x, _motors.limit.roll));
|
||||||
_motors.set_roll_ff(get_rate_roll_pid().get_ff());
|
_motors.set_roll_ff(get_rate_roll_pid().get_ff());
|
||||||
|
|
||||||
_motors.set_pitch(get_rate_pitch_pid().update_all(_rate_target_ang_vel.y, gyro_latest.y, _motors.limit.roll_pitch));
|
_motors.set_pitch(get_rate_pitch_pid().update_all(_rate_target_ang_vel.y, gyro_latest.y, _motors.limit.pitch));
|
||||||
_motors.set_pitch_ff(get_rate_pitch_pid().get_ff());
|
_motors.set_pitch_ff(get_rate_pitch_pid().get_ff());
|
||||||
|
|
||||||
_motors.set_yaw(get_rate_yaw_pid().update_all(_rate_target_ang_vel.z, gyro_latest.z, _motors.limit.yaw));
|
_motors.set_yaw(get_rate_yaw_pid().update_all(_rate_target_ang_vel.z, gyro_latest.z, _motors.limit.yaw));
|
||||||
|
@ -335,8 +335,8 @@ void AC_AttitudeControl_Sub::rate_controller_run()
|
|||||||
update_throttle_rpy_mix();
|
update_throttle_rpy_mix();
|
||||||
|
|
||||||
Vector3f gyro_latest = _ahrs.get_gyro_latest();
|
Vector3f gyro_latest = _ahrs.get_gyro_latest();
|
||||||
_motors.set_roll(get_rate_roll_pid().update_all(_rate_target_ang_vel.x, gyro_latest.x, _motors.limit.roll_pitch));
|
_motors.set_roll(get_rate_roll_pid().update_all(_rate_target_ang_vel.x, gyro_latest.x, _motors.limit.roll));
|
||||||
_motors.set_pitch(get_rate_pitch_pid().update_all(_rate_target_ang_vel.y, gyro_latest.y, _motors.limit.roll_pitch));
|
_motors.set_pitch(get_rate_pitch_pid().update_all(_rate_target_ang_vel.y, gyro_latest.y, _motors.limit.pitch));
|
||||||
_motors.set_yaw(get_rate_yaw_pid().update_all(_rate_target_ang_vel.z, gyro_latest.z, _motors.limit.yaw));
|
_motors.set_yaw(get_rate_yaw_pid().update_all(_rate_target_ang_vel.z, gyro_latest.z, _motors.limit.yaw));
|
||||||
|
|
||||||
control_monitor_update();
|
control_monitor_update();
|
||||||
|
Loading…
Reference in New Issue
Block a user