mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AttControl: fix set_yaw_target_to_current_heading
This commit is contained in:
parent
011bc0a350
commit
ac04fcd836
@ -108,7 +108,7 @@ public:
|
||||
void reset_rate_controller_I_terms();
|
||||
|
||||
// Sets yaw target to vehicle heading
|
||||
void set_yaw_target_to_current_heading() { _attitude_target_euler_angle.z = _ahrs.yaw; }
|
||||
void set_yaw_target_to_current_heading() { shift_ef_yaw_target(degrees(_ahrs.yaw - _attitude_target_euler_angle.z)*100.0f); }
|
||||
|
||||
// Shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centidegrees and is added to the current target heading
|
||||
void shift_ef_yaw_target(float yaw_shift_cd);
|
||||
|
Loading…
Reference in New Issue
Block a user