Copter: make Copter use milligauss

The telemetry and and logging is still in compass units, though. This
way, users won't need to recalibrate their compasses.
This commit is contained in:
Staroselskii Georgii 2015-08-24 17:54:55 +03:00 committed by Andrew Tridgell
parent 4b948f5bb1
commit 68e0d57998
4 changed files with 10 additions and 10 deletions

View File

@ -124,7 +124,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
// store initial x,y,z compass values
// initialise interference percentage
for (uint8_t i=0; i<compass.get_count(); i++) {
compass_base[i] = compass.get_field(i);
compass_base[i] = compass.get_field_milligauss(i);
interference_pct[i] = 0.0f;
}
@ -167,7 +167,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
// if throttle is near zero, update base x,y,z values
if (throttle_pct <= 0.0f) {
for (uint8_t i=0; i<compass.get_count(); i++) {
compass_base[i] = compass_base[i] * 0.99f + compass.get_field(i) * 0.01f;
compass_base[i] = compass_base[i] * 0.99f + compass.get_field_milligauss(i) * 0.01f;
}
// causing printing to happen as soon as throttle is lifted
@ -175,7 +175,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
// calculate diff from compass base and scale with throttle
for (uint8_t i=0; i<compass.get_count(); i++) {
motor_impact[i] = compass.get_field(i) - compass_base[i];
motor_impact[i] = compass.get_field_milligauss(i) - compass_base[i];
}
// throttle based compensation

View File

@ -356,7 +356,7 @@ bool Copter::pre_arm_checks(bool display_failure)
}
// check for unreasonable compass offsets
Vector3f offsets = compass.get_offsets();
Vector3f offsets = compass.get_offsets_milligauss();
if(offsets.length() > COMPASS_OFFSETS_MAX) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass offsets too high"));
@ -365,7 +365,7 @@ bool Copter::pre_arm_checks(bool display_failure)
}
// check for unreasonable mag field length
float mag_field = compass.get_field().length();
float mag_field = compass.get_field_milligauss().length();
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check mag field"));
@ -376,11 +376,11 @@ bool Copter::pre_arm_checks(bool display_failure)
#if COMPASS_MAX_INSTANCES > 1
// check all compasses point in roughly same direction
if (compass.get_count() > 1) {
Vector3f prime_mag_vec = compass.get_field();
Vector3f prime_mag_vec = compass.get_field_milligauss();
prime_mag_vec.normalize();
for(uint8_t i=0; i<compass.get_count(); i++) {
// get next compass
Vector3f mag_vec = compass.get_field(i);
Vector3f mag_vec = compass.get_field_milligauss(i);
mag_vec.normalize();
Vector3f vec_diff = mag_vec - prime_mag_vec;
if (compass.use_for_yaw(i) && vec_diff.length() > COMPASS_ACCEPTABLE_VECTOR_DIFF) {

View File

@ -450,7 +450,7 @@ void Copter::report_compass()
// mag offsets
Vector3f offsets;
for (uint8_t i=0; i<compass.get_count(); i++) {
offsets = compass.get_offsets(i);
offsets = compass.get_offsets_milligauss(i);
// mag offsets
cliSerial->printf_P(PSTR("Mag%d off: %4.4f, %4.4f, %4.4f\n"),
(int)i,

View File

@ -117,8 +117,8 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
counter++;
if (counter>20) {
if (compass.healthy()) {
const Vector3f &mag_ofs = compass.get_offsets();
const Vector3f &mag = compass.get_field();
const Vector3f &mag_ofs = compass.get_offsets_milligauss();
const Vector3f &mag = compass.get_field_milligauss();
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
(wrap_360_cd(ToDeg(heading) * 100)) /100,
(double)mag.x,