AP_Compass: remove use of milligauss_ratio

Now, we have all current compasses publishing their values already in
milligauss, so there's no need for that variable anymore.
This commit is contained in:
Gustavo Jose de Sousa 2015-09-29 16:32:53 -03:00 committed by Randy Mackay
parent b603641d7c
commit 9927cf066f
8 changed files with 2 additions and 20 deletions

View File

@ -180,8 +180,6 @@ bool AP_Compass_AK8963::init()
set_dev_id(_compass_instance, _bus->get_dev_id());
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void));
set_milligauss_ratio(_compass_instance, 1.0f);
_bus_sem->give();
hal.scheduler->resume_timer_procs();

View File

@ -141,9 +141,3 @@ void AP_Compass_Backend::set_external(uint8_t instance, bool external)
{
_compass._state[instance].external.set(external);
}
// set ratio to convert to milligauss
void AP_Compass_Backend::set_milligauss_ratio(uint8_t instance, float ratio)
{
_compass._state[instance].milligauss_ratio = ratio;
}

View File

@ -73,9 +73,6 @@ protected:
// set external state for an instance
void set_external(uint8_t instance, bool external);
// set ratio to convert to milligauss
void set_milligauss_ratio(uint8_t instance, float ratio);
// access to frontend
Compass &_compass;

View File

@ -53,7 +53,6 @@ AP_Compass_HIL::init(void)
// register two compass instances
for (uint8_t i=0; i<HIL_NUM_COMPASSES; i++) {
_compass_instance[i] = register_compass();
set_milligauss_ratio(_compass_instance[i], 1.0f);
}
return true;
}

View File

@ -332,8 +332,6 @@ AP_Compass_HMC5843::init()
_compass_instance = register_compass();
set_dev_id(_compass_instance, _product_id);
set_milligauss_ratio(_compass_instance, 1.0f);
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
set_external(_compass_instance, true);
#endif

View File

@ -341,8 +341,6 @@ AP_Compass_LSM303D::init()
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Compass_LSM303D::_update, void));
set_milligauss_ratio(_compass_instance, 1.0f);
_spi_sem->give();
hal.scheduler->resume_timer_procs();
_initialised = true;

View File

@ -96,7 +96,6 @@ bool AP_Compass_PX4::init(void)
_count[i] = 0;
_sum[i].zero();
set_milligauss_ratio(_instance[i], 1.0f);
}
// give the driver a chance to run, and gather one sample

View File

@ -119,7 +119,7 @@ public:
uint8_t get_count(void) const { return _compass_count; }
/// Return the current field as a Vector3f
const Vector3f &get_field(uint8_t i) const { return _state[i].field * _state[i].milligauss_ratio; }
const Vector3f &get_field(uint8_t i) const { return _state[i].field; }
const Vector3f &get_field(void) const { return get_field(get_primary()); }
// raw/unfiltered measurement interface
@ -180,7 +180,7 @@ public:
///
/// @returns The current compass offsets.
///
const Vector3f &get_offsets(uint8_t i) const { return _state[i].offset * _state[i].milligauss_ratio; }
const Vector3f &get_offsets(uint8_t i) const { return _state[i].offset; }
const Vector3f &get_offsets(void) const { return get_offsets(get_primary()); }
/// Sets the initial location used to get declination
@ -391,7 +391,6 @@ private:
// corrected magnetic field strength
Vector3f field;
float milligauss_ratio;
// when we last got data
uint32_t last_update_ms;