Browse Source

AP_AHRS: Added getters for compass and GPS.

master
Michael Day 11 years ago committed by Andrew Tridgell
parent
commit
e5addf86c1
  1. 10
      libraries/AP_AHRS/AP_AHRS.h

10
libraries/AP_AHRS/AP_AHRS.h

@ -38,6 +38,7 @@ class AP_AHRS @@ -38,6 +38,7 @@ class AP_AHRS
public:
// Constructor
AP_AHRS(AP_InertialSensor &ins, GPS *&gps) :
_compass(NULL),
_ins(ins),
_gps(gps)
{
@ -74,7 +75,10 @@ public: @@ -74,7 +75,10 @@ public:
set_orientation();
}
const Compass* get_compass() const {
return _compass;
}
// allow for runtime change of orientation
// this makes initial config easier
void set_orientation() {
@ -88,6 +92,10 @@ public: @@ -88,6 +92,10 @@ public:
_airspeed = airspeed;
}
const GPS *get_gps() const {
return _gps;
}
const AP_InertialSensor &get_ins() const {
return _ins;
}

Loading…
Cancel
Save