mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Compass: don't save the orientation to EEPROM
there is no point in saving this, the value is only configurable at compile time for now, and is always set
This commit is contained in:
parent
cc1961b1e8
commit
a20f57c59e
@ -264,7 +264,7 @@ bool AP_Compass_HMC5843::read()
|
|||||||
|
|
||||||
// rotate to the desired orientation
|
// rotate to the desired orientation
|
||||||
Vector3f rot_mag = Vector3f(mag_x,mag_y,mag_z);
|
Vector3f rot_mag = Vector3f(mag_x,mag_y,mag_z);
|
||||||
rot_mag.rotate((enum Rotation)_orientation.get());
|
rot_mag.rotate(_orientation);
|
||||||
if (product_id == AP_COMPASS_TYPE_HMC5883L) {
|
if (product_id == AP_COMPASS_TYPE_HMC5883L) {
|
||||||
rot_mag.rotate(ROTATION_YAW_90);
|
rot_mag.rotate(ROTATION_YAW_90);
|
||||||
}
|
}
|
||||||
@ -282,5 +282,5 @@ bool AP_Compass_HMC5843::read()
|
|||||||
void
|
void
|
||||||
AP_Compass_HMC5843::set_orientation(enum Rotation rotation)
|
AP_Compass_HMC5843::set_orientation(enum Rotation rotation)
|
||||||
{
|
{
|
||||||
_orientation.set_and_save(rotation);
|
_orientation = rotation;
|
||||||
}
|
}
|
||||||
|
@ -7,7 +7,6 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
|||||||
AP_GROUPINFO("DEC", 2, Compass, _declination),
|
AP_GROUPINFO("DEC", 2, Compass, _declination),
|
||||||
AP_GROUPINFO("LEARN", 3, Compass, _learn), // true if learning calibration
|
AP_GROUPINFO("LEARN", 3, Compass, _learn), // true if learning calibration
|
||||||
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw), // true if used for DCM yaw
|
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw), // true if used for DCM yaw
|
||||||
AP_GROUPINFO("ORIENT", 5, Compass, _orientation),
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -21,9 +20,9 @@ Compass::Compass(void) :
|
|||||||
_learn(1),
|
_learn(1),
|
||||||
_use_for_yaw(1),
|
_use_for_yaw(1),
|
||||||
_null_enable(false),
|
_null_enable(false),
|
||||||
_null_init_done(false)
|
_null_init_done(false),
|
||||||
|
_orientation(ROTATION_NONE)
|
||||||
{
|
{
|
||||||
_orientation.set(ROTATION_NONE);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Default init method, just returns success.
|
// Default init method, just returns success.
|
||||||
@ -37,7 +36,7 @@ Compass::init()
|
|||||||
void
|
void
|
||||||
Compass::set_orientation(enum Rotation rotation)
|
Compass::set_orientation(enum Rotation rotation)
|
||||||
{
|
{
|
||||||
_orientation.set_and_save(rotation);
|
_orientation = rotation;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
@ -119,7 +119,7 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_Int8 _orientation;
|
enum Rotation _orientation;
|
||||||
AP_Vector3f _offset;
|
AP_Vector3f _offset;
|
||||||
AP_Float _declination;
|
AP_Float _declination;
|
||||||
AP_Int8 _learn; ///<enable calibration learning
|
AP_Int8 _learn; ///<enable calibration learning
|
||||||
|
Loading…
Reference in New Issue
Block a user