mirror of https://github.com/ArduPilot/ardupilot
AC_AttControl: add shift_ef_yaw_target
This allows shifting the target heading in case the EKF shifts it's heading estimate
This commit is contained in:
parent
e3ccb74e12
commit
1e3e65e443
|
@ -86,6 +86,12 @@ void AC_AttitudeControl::relax_bf_rate_controller()
|
|||
_pid_rate_yaw.reset_I();
|
||||
}
|
||||
|
||||
// shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centi-degreesa and is added to the current target heading
|
||||
void AC_AttitudeControl::shift_ef_yaw_target(float yaw_shift_cd)
|
||||
{
|
||||
_angle_ef_target.z = wrap_360_cd_float(_angle_ef_target.z + yaw_shift_cd);
|
||||
}
|
||||
|
||||
//
|
||||
// methods to be called by upper controllers to request and implement a desired attitude
|
||||
//
|
||||
|
|
|
@ -111,6 +111,9 @@ public:
|
|||
// set_yaw_target_to_current_heading - sets yaw target to current heading
|
||||
void set_yaw_target_to_current_heading() { _angle_ef_target.z = _ahrs.yaw_sensor; }
|
||||
|
||||
// shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centi-degreesa and is added to the current target heading
|
||||
void shift_ef_yaw_target(float yaw_shift_cd);
|
||||
|
||||
//
|
||||
// methods to be called by upper controllers to request and implement a desired attitude
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue