mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Compass: use constructor to set initial values for _learn and _use_for_yaw
this ensures they are set if you have MAG_ENABLE==0
This commit is contained in:
parent
900388a85a
commit
d0a6359b37
@ -138,9 +138,6 @@ AP_Compass_HMC5843::init()
|
|||||||
uint16_t expected_yz = 715;
|
uint16_t expected_yz = 715;
|
||||||
float gain_multiple = 1.0;
|
float gain_multiple = 1.0;
|
||||||
|
|
||||||
// call the parent class init for common code
|
|
||||||
Compass::init();
|
|
||||||
|
|
||||||
delay(10);
|
delay(10);
|
||||||
|
|
||||||
// determine if we are using 5843 or 5883L
|
// determine if we are using 5843 or 5883L
|
||||||
|
@ -18,6 +18,8 @@ Compass::Compass(void) :
|
|||||||
_declination (0.0),
|
_declination (0.0),
|
||||||
_null_init_done(false),
|
_null_init_done(false),
|
||||||
_null_enable(false),
|
_null_enable(false),
|
||||||
|
_learn(1),
|
||||||
|
_use_for_yaw(1),
|
||||||
product_id(AP_COMPASS_TYPE_UNKNOWN)
|
product_id(AP_COMPASS_TYPE_UNKNOWN)
|
||||||
{
|
{
|
||||||
// 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
|
||||||
@ -25,21 +27,11 @@ Compass::Compass(void) :
|
|||||||
_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
|
||||||
Compass::init()
|
Compass::init()
|
||||||
{
|
{
|
||||||
// enable learning by default
|
|
||||||
if (!_learn.load()) {
|
|
||||||
_learn.set(1);
|
|
||||||
}
|
|
||||||
// enable use for yaw calculation by default
|
|
||||||
if (!_use_for_yaw.load()) {
|
|
||||||
_use_for_yaw.set(1);
|
|
||||||
}
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user