mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AC_AttitudeControl: add get for angle bf errors
This commit is contained in:
parent
88be3d67e7
commit
4d9da2720b
@ -140,6 +140,9 @@ public:
|
||||
// angle_ef_targets - returns angle controller earth-frame targets (for reporting)
|
||||
const Vector3f& angle_ef_targets() const { return _angle_ef_target; }
|
||||
|
||||
// angle_bf_error - returns angle controller body-frame errors (for stability checking)
|
||||
const Vector3f& angle_bf_error() const { return _angle_bf_error; }
|
||||
|
||||
// rate_bf_targets - sets rate controller body-frame targets
|
||||
void rate_bf_roll_target(float rate_cds) { _rate_bf_target.x = rate_cds; }
|
||||
void rate_bf_pitch_target(float rate_cds) { _rate_bf_target.y = rate_cds; }
|
||||
|
Loading…
Reference in New Issue
Block a user