mirror of https://github.com/ArduPilot/ardupilot
Compass: updates for new AP_Param API
This commit is contained in:
parent
53470aff09
commit
c181498e36
|
@ -21,6 +21,7 @@ Compass::Compass(void) :
|
|||
_orientation(ROTATION_NONE),
|
||||
_null_init_done(false)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
// Default init method, just returns success.
|
||||
|
|
Loading…
Reference in New Issue