Blimp: Guided Yaw Fix

This commit is contained in:
Leonard Hall 2023-03-04 19:17:05 +10:30 committed by Randy Mackay
parent 715bb6e705
commit bfbc76e172

View File

@ -116,10 +116,6 @@ public:
{
public:
// yaw(): main product of AutoYaw; the heading:
float yaw();
// mode(): current method of determining desired yaw:
autopilot_yaw_mode mode() const
{
@ -129,8 +125,6 @@ public:
void set_mode(autopilot_yaw_mode new_mode);
autopilot_yaw_mode default_mode(bool rtl) const;
// rate_cds(): desired yaw rate in centidegrees/second:
float rate_cds() const;
void set_rate(float new_rate_cds);
// set_roi(...): set a "look at" location:
@ -143,6 +137,12 @@ public:
private:
// yaw_cd(): main product of AutoYaw; the heading:
float yaw_cd();
// rate_cds(): desired yaw rate in centidegrees/second:
float rate_cds();
float look_ahead_yaw();
float roi_yaw();
@ -164,9 +164,6 @@ public:
// heading when in yaw_look_ahead_yaw
float _look_ahead_yaw;
// turn rate (in cds) when auto_yaw_mode is set to AUTO_YAW_RATE
float _rate_cds;
// used to reduce update rate to 100hz:
uint8_t roi_yaw_counter;