mirror of https://github.com/ArduPilot/ardupilot
Added accessors declination.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1677 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e6e161d56d
commit
385e3af27e
|
@ -54,6 +54,14 @@ Compass::set_declination(float radians)
|
|||
_declination.set_and_save(radians);
|
||||
}
|
||||
|
||||
float
|
||||
Compass::get_declination()
|
||||
{
|
||||
return _declination.get();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void
|
||||
Compass::calculate(float roll, float pitch)
|
||||
{
|
||||
|
|
|
@ -107,6 +107,7 @@ public:
|
|||
/// @param radians Local field declination.
|
||||
///
|
||||
virtual void set_declination(float radians);
|
||||
float get_declination();
|
||||
|
||||
protected:
|
||||
AP_Var_group _group; ///< storage group holding the compass' calibration data
|
||||
|
|
Loading…
Reference in New Issue