mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: Fix some typos
Fixed some typos found in the code.
This commit is contained in:
parent
4e7d5e9ecf
commit
633bb159bf
@ -89,7 +89,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if AP_COMPASS_DIAGONALS_ENABLED
|
#if AP_COMPASS_DIAGONALS_ENABLED
|
||||||
// apply eliptical correction
|
// apply elliptical correction
|
||||||
if (!diagonals.is_zero()) {
|
if (!diagonals.is_zero()) {
|
||||||
Matrix3f mat(
|
Matrix3f mat(
|
||||||
diagonals.x, offdiagonals.x, offdiagonals.y,
|
diagonals.x, offdiagonals.x, offdiagonals.y,
|
||||||
@ -123,7 +123,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
we apply the motor offsets after we apply the eliptical
|
we apply the motor offsets after we apply the elliptical
|
||||||
correction. This is needed to match the way that the motor
|
correction. This is needed to match the way that the motor
|
||||||
compensation values are calculated, as they are calculated based
|
compensation values are calculated, as they are calculated based
|
||||||
on final field outputs, not on the raw outputs
|
on final field outputs, not on the raw outputs
|
||||||
@ -251,7 +251,7 @@ void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation)
|
|||||||
static constexpr float FILTER_KOEF = 0.1f;
|
static constexpr float FILTER_KOEF = 0.1f;
|
||||||
|
|
||||||
/* Check that the compass value is valid by using a mean filter. If
|
/* Check that the compass value is valid by using a mean filter. If
|
||||||
* the value is further than filtrer_range from mean value, it is
|
* the value is further than filter_range from mean value, it is
|
||||||
* rejected.
|
* rejected.
|
||||||
*/
|
*/
|
||||||
bool AP_Compass_Backend::field_ok(const Vector3f &field)
|
bool AP_Compass_Backend::field_ok(const Vector3f &field)
|
||||||
|
@ -92,7 +92,7 @@ protected:
|
|||||||
* 2. publish_raw_field - this provides an uncorrected point-sample for
|
* 2. publish_raw_field - this provides an uncorrected point-sample for
|
||||||
* calibration libraries
|
* calibration libraries
|
||||||
* 3. correct_field - this corrects the measurement in-place for hard iron,
|
* 3. correct_field - this corrects the measurement in-place for hard iron,
|
||||||
* soft iron, motor interference, and non-orthagonality errors
|
* soft iron, motor interference, and non-orthogonality errors
|
||||||
* 4. publish_filtered_field - legacy filtered magnetic field
|
* 4. publish_filtered_field - legacy filtered magnetic field
|
||||||
*
|
*
|
||||||
* All those functions expect the mag field to be in milligauss.
|
* All those functions expect the mag field to be in milligauss.
|
||||||
|
@ -464,8 +464,8 @@ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const
|
|||||||
field = get_field(instance);
|
field = get_field(instance);
|
||||||
|
|
||||||
#if AP_COMPASS_DIAGONALS_ENABLED
|
#if AP_COMPASS_DIAGONALS_ENABLED
|
||||||
// form eliptical correction matrix and invert it. This is
|
// form elliptical correction matrix and invert it. This is
|
||||||
// needed to remove the effects of the eliptical correction
|
// needed to remove the effects of the elliptical correction
|
||||||
// when calculating new offsets
|
// when calculating new offsets
|
||||||
const Vector3f &diagonals = get_diagonals(instance);
|
const Vector3f &diagonals = get_diagonals(instance);
|
||||||
if (!diagonals.is_zero()) {
|
if (!diagonals.is_zero()) {
|
||||||
|
@ -93,7 +93,7 @@ AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)
|
|||||||
|
|
||||||
bool AP_Compass_DroneCAN::init()
|
bool AP_Compass_DroneCAN::init()
|
||||||
{
|
{
|
||||||
// Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default
|
// Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default
|
||||||
if (!register_compass(_devid, _instance)) {
|
if (!register_compass(_devid, _instance)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -120,7 +120,7 @@ AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_d
|
|||||||
}
|
}
|
||||||
|
|
||||||
bool already_detected = false;
|
bool already_detected = false;
|
||||||
// Check if there's an empty spot for possible registeration
|
// Check if there's an empty spot for possible registration
|
||||||
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
|
for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
|
||||||
if (_detected_modules[i].ap_dronecan == ap_dronecan &&
|
if (_detected_modules[i].ap_dronecan == ap_dronecan &&
|
||||||
_detected_modules[i].node_id == node_id &&
|
_detected_modules[i].node_id == node_id &&
|
||||||
|
@ -38,7 +38,7 @@
|
|||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Defaul address: 0x1E
|
* Default address: 0x1E
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define HMC5843_REG_CONFIG_A 0x00
|
#define HMC5843_REG_CONFIG_A 0x00
|
||||||
|
@ -70,7 +70,7 @@ AP_Compass_MMC5XX3::AP_Compass_MMC5XX3(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
|||||||
|
|
||||||
bool AP_Compass_MMC5XX3::init()
|
bool AP_Compass_MMC5XX3::init()
|
||||||
{
|
{
|
||||||
// take i2c bus sempahore
|
// take i2c bus semaphore
|
||||||
WITH_SEMAPHORE(dev->get_semaphore());
|
WITH_SEMAPHORE(dev->get_semaphore());
|
||||||
|
|
||||||
dev->set_retries(10);
|
dev->set_retries(10);
|
||||||
|
@ -51,7 +51,7 @@ AP_Compass_SITL::AP_Compass_SITL()
|
|||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
create correction matrix for diagnonals and off-diagonals
|
create correction matrix for diagonals and off-diagonals
|
||||||
*/
|
*/
|
||||||
void AP_Compass_SITL::_setup_eliptical_correcion(uint8_t i)
|
void AP_Compass_SITL::_setup_eliptical_correcion(uint8_t i)
|
||||||
{
|
{
|
||||||
|
@ -241,7 +241,7 @@ private:
|
|||||||
bool _is_external; // true if compass is external (provided by caller)
|
bool _is_external; // true if compass is external (provided by caller)
|
||||||
bool _check_orientation; // true if orientation should be automatically checked
|
bool _check_orientation; // true if orientation should be automatically checked
|
||||||
bool _fix_orientation; // true if orientation should be fixed if necessary
|
bool _fix_orientation; // true if orientation should be fixed if necessary
|
||||||
bool _always_45_deg; // true if orentation should considder 45deg with equal tolerance
|
bool _always_45_deg; // true if orientation should consider 45deg with equal tolerance
|
||||||
float _orientation_confidence; // measure of confidence in automatic orientation detection
|
float _orientation_confidence; // measure of confidence in automatic orientation detection
|
||||||
CompassSample _last_sample;
|
CompassSample _last_sample;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user