AP_AHRS: make AHRS attitude member variables private

This commit is contained in:
Peter Barker 2024-01-12 23:40:22 +11:00 committed by Peter Barker
parent c7c2c54c26
commit f7e94bcc75
2 changed files with 8 additions and 7 deletions

View File

@ -548,10 +548,6 @@ public:
*/
// roll/pitch/yaw euler angles, all in radians
float roll;
float pitch;
float yaw;
float get_roll() const { return roll; }
float get_pitch() const { return pitch; }
float get_yaw() const { return yaw; }
@ -681,6 +677,11 @@ public:
private:
// roll/pitch/yaw euler angles, all in radians
float roll;
float pitch;
float yaw;
// optional view class
AP_AHRS_View *_view;

View File

@ -84,9 +84,9 @@ void loop(void)
hal.console->printf(
"r:%4.1f p:%4.1f y:%4.1f "
"drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n",
(double)ToDeg(ahrs.roll),
(double)ToDeg(ahrs.pitch),
(double)ToDeg(ahrs.yaw),
(double)ToDeg(ahrs.get_roll()),
(double)ToDeg(ahrs.get_pitch()),
(double)ToDeg(ahrs.get_yaw()),
(double)ToDeg(drift.x),
(double)ToDeg(drift.y),
(double)ToDeg(drift.z),