mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_Compass: remove use of Vector3 as function
This commit is contained in:
parent
8c0aed9c6c
commit
0f2bcea647
@ -1677,7 +1677,7 @@ const Vector3f& Compass::getHIL(uint8_t instance) const
|
|||||||
void Compass::_setup_earth_field(void)
|
void Compass::_setup_earth_field(void)
|
||||||
{
|
{
|
||||||
// assume a earth field strength of 400
|
// assume a earth field strength of 400
|
||||||
_hil.Bearth(400, 0, 0);
|
_hil.Bearth = {400, 0, 0};
|
||||||
|
|
||||||
// rotate _Bearth for inclination and declination. -66 degrees
|
// rotate _Bearth for inclination and declination. -66 degrees
|
||||||
// is the inclination in Canberra, Australia
|
// is the inclination in Canberra, Australia
|
||||||
|
@ -138,7 +138,6 @@ void AP_Compass_LIS3MDL::timer()
|
|||||||
int16_t magz;
|
int16_t magz;
|
||||||
} data;
|
} data;
|
||||||
const float range_scale = 1000.0f / 6842.0f;
|
const float range_scale = 1000.0f / 6842.0f;
|
||||||
Vector3f field;
|
|
||||||
|
|
||||||
// check data ready
|
// check data ready
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
@ -154,9 +153,15 @@ void AP_Compass_LIS3MDL::timer()
|
|||||||
goto check_registers;
|
goto check_registers;
|
||||||
}
|
}
|
||||||
|
|
||||||
field(data.magx * range_scale, data.magy * range_scale, data.magz * range_scale);
|
{
|
||||||
|
Vector3f field{
|
||||||
|
data.magx * range_scale,
|
||||||
|
data.magy * range_scale,
|
||||||
|
data.magz * range_scale,
|
||||||
|
};
|
||||||
|
|
||||||
accumulate_sample(field, compass_instance);
|
accumulate_sample(field, compass_instance);
|
||||||
|
}
|
||||||
|
|
||||||
check_registers:
|
check_registers:
|
||||||
dev->check_next_register();
|
dev->check_next_register();
|
||||||
|
@ -177,7 +177,6 @@ void AP_Compass_RM3100::timer()
|
|||||||
uint8_t magz_1;
|
uint8_t magz_1;
|
||||||
uint8_t magz_0;
|
uint8_t magz_0;
|
||||||
} data;
|
} data;
|
||||||
Vector3f field;
|
|
||||||
|
|
||||||
int32_t magx = 0;
|
int32_t magx = 0;
|
||||||
int32_t magy = 0;
|
int32_t magy = 0;
|
||||||
@ -209,10 +208,16 @@ void AP_Compass_RM3100::timer()
|
|||||||
magy >>= 8;
|
magy >>= 8;
|
||||||
magz >>= 8;
|
magz >>= 8;
|
||||||
|
|
||||||
|
{
|
||||||
// apply scaler and store in field vector
|
// apply scaler and store in field vector
|
||||||
field(magx * _scaler, magy * _scaler, magz * _scaler);
|
Vector3f field{
|
||||||
|
magx * _scaler,
|
||||||
|
magy * _scaler,
|
||||||
|
magz * _scaler
|
||||||
|
};
|
||||||
|
|
||||||
accumulate_sample(field, compass_instance);
|
accumulate_sample(field, compass_instance);
|
||||||
|
}
|
||||||
|
|
||||||
check_registers:
|
check_registers:
|
||||||
dev->check_next_register();
|
dev->check_next_register();
|
||||||
|
@ -51,7 +51,7 @@ void AP_Compass_SITL::_setup_eliptical_correcion(uint8_t i)
|
|||||||
{
|
{
|
||||||
Vector3f diag = _sitl->mag_diag[i].get();
|
Vector3f diag = _sitl->mag_diag[i].get();
|
||||||
if (diag.is_zero()) {
|
if (diag.is_zero()) {
|
||||||
diag(1,1,1);
|
diag = {1,1,1};
|
||||||
}
|
}
|
||||||
const Vector3f &diagonals = diag;
|
const Vector3f &diagonals = diag;
|
||||||
const Vector3f &offdiagonals = _sitl->mag_offdiag[i];
|
const Vector3f &offdiagonals = _sitl->mag_offdiag[i];
|
||||||
|
Loading…
Reference in New Issue
Block a user