From 1ff07762de4ea4341123a2cb92eb7921aa4238f4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 2 Jan 2020 10:38:03 +1100 Subject: [PATCH] Copter: remove report_compass method This wasn't actually responsible for saving offsets any more. The data spewed out was rather unlikely to be seen, and will be present in logs anyway. --- ArduCopter/Copter.h | 6 ---- ArduCopter/compassmot.cpp | 3 -- ArduCopter/setup.cpp | 74 --------------------------------------- 3 files changed, 83 deletions(-) delete mode 100644 ArduCopter/setup.cpp diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e8c66c8321..3e5dec6632 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -859,12 +859,6 @@ private: void winch_init(); void winch_update(); - // setup.cpp - void report_compass(); - void print_blanks(int16_t num); - void print_divider(void); - void print_enabled(bool b); - // switches.cpp void save_trim(); void auto_trim(); diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 8795e83f45..b8c06d3048 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -248,9 +248,6 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED); } - // display new motor offsets and save - report_compass(); - // turn off notify leds AP_Notify::flags.esc_calibration = false; diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp deleted file mode 100644 index 4fd0cf5aa4..0000000000 --- a/ArduCopter/setup.cpp +++ /dev/null @@ -1,74 +0,0 @@ -#include "Copter.h" - -// report_compass - displays compass information. Also called by compassmot.pde -void Copter::report_compass() -{ - hal.console->printf("Compass\n"); - print_divider(); - - print_enabled(AP::compass().enabled()); - - // mag declination - hal.console->printf("Mag Dec: %4.4f\n", - (double)degrees(compass.get_declination())); - - // mag offsets - Vector3f offsets; - for (uint8_t i=0; iprintf("Mag%d off: %4.4f, %4.4f, %4.4f\n", - (int)i, - (double)offsets.x, - (double)offsets.y, - (double)offsets.z); - } - - // motor compensation - hal.console->printf("Motor Comp: "); - if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) { - hal.console->printf("Off\n"); - }else{ - if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) { - hal.console->printf("Throttle"); - } - if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) { - hal.console->printf("Current"); - } - Vector3f motor_compensation; - for (uint8_t i=0; iprintf("\nComMot%d: %4.2f, %4.2f, %4.2f\n", - (int)i, - (double)motor_compensation.x, - (double)motor_compensation.y, - (double)motor_compensation.z); - } - } - print_blanks(1); -} - -void Copter::print_blanks(int16_t num) -{ - while(num > 0) { - num--; - hal.console->printf("\n"); - } -} - -void Copter::print_divider(void) -{ - for (int i = 0; i < 40; i++) { - hal.console->printf("-"); - } - hal.console->printf("\n"); -} - -void Copter::print_enabled(bool b) -{ - if(b) - hal.console->printf("en"); - else - hal.console->printf("dis"); - hal.console->printf("abled\n"); -}