mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
added names to output in show
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1698 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
7acf9a15fc
commit
0ff00e3a53
@ -5,10 +5,10 @@
|
|||||||
// their values.
|
// their values.
|
||||||
//
|
//
|
||||||
Compass::Compass(AP_Var::Key key) :
|
Compass::Compass(AP_Var::Key key) :
|
||||||
_group(key),
|
_group(key, PSTR("COMPASS_")),
|
||||||
_orientation_matrix(&_group, 0),
|
_orientation_matrix (&_group, 0),
|
||||||
_offset(&_group, 1),
|
_offset (&_group, 1),
|
||||||
_declination(&_group, 2, 0.0),
|
_declination (&_group, 2, 0.0, PSTR("DEC")),
|
||||||
_null_init_done(false)
|
_null_init_done(false)
|
||||||
{
|
{
|
||||||
// Default the orientation matrix to none - will be overridden at group load time
|
// Default the orientation matrix to none - will be overridden at group load time
|
||||||
@ -16,6 +16,8 @@ Compass::Compass(AP_Var::Key key) :
|
|||||||
_orientation_matrix.set(ROTATION_NONE);
|
_orientation_matrix.set(ROTATION_NONE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//_group
|
||||||
|
|
||||||
// Default init method, just returns success.
|
// Default init method, just returns success.
|
||||||
//
|
//
|
||||||
bool
|
bool
|
||||||
|
Loading…
Reference in New Issue
Block a user