diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 4d5db5d3d7..a66d35fcc7 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -15,7 +15,6 @@ //#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally) //#define AC_TERRAIN DISABLED // disable terrain library //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash -//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands //#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space //#define VISUAL_ODOMETRY_ENABLED DISABLED // disable visual odometry to save 2K of flash space diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 59e45a36e4..233cd212c9 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -162,8 +162,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { void Copter::setup() { - cliSerial = hal.console; - // Load the default values of variables listed in var_info[]s AP_Param::setup_sketch_defaults(); diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e8c7c19d05..6fd6ed4c18 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -30,7 +30,6 @@ // Common dependencies #include #include -#include #include #include @@ -168,10 +167,6 @@ private: AP_Vehicle::MultiCopter aparm; - // cliSerial isn't strictly necessary - it is an alias for hal.console. It may - // be deprecated in favor of hal.console in later releases. - AP_HAL::BetterStream* cliSerial; - // Global parameters are all contained within the 'g' class. Parameters g; ParametersG2 g2; @@ -720,7 +715,6 @@ private: void send_pid_tuning(mavlink_channel_t chan); void gcs_data_stream_send(void); void gcs_check_input(void); - void do_erase_logs(void); void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt); void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds); void Log_Write_Current(); @@ -751,7 +745,6 @@ private: void Log_Write_Proximity(); void Log_Write_Beacon(); void Log_Write_Vehicle_Startup_Messages(); - void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page); void load_parameters(void); void convert_pid_parameters(void); void userhook_init(); @@ -1058,16 +1051,6 @@ private: void terrain_update(); void terrain_logging(); bool terrain_use(); - void report_batt_monitor(); - void report_frame(); - void report_radio(); - void report_ins(); - void report_flight_modes(); - void report_optflow(); - void print_radio_values(); - void print_switch(uint8_t p, uint8_t m, bool b); - void print_accel_offsets_and_scaling(void); - void print_gyro_offsets(void); void report_compass(); void print_blanks(int16_t num); void print_divider(void); @@ -1149,9 +1132,7 @@ private: bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); void auto_spline_start(const Location_Class& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location_Class& next_destination); - void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode); void log_init(void); - void run_cli(AP_HAL::UARTDriver *port); void init_capabilities(void); void dataflash_periodic(void); void accel_cal_update(void); @@ -1159,33 +1140,8 @@ private: public: void mavlink_delay_cb(); void failsafe_check(); - int8_t dump_log(uint8_t argc, const Menu::arg *argv); - int8_t erase_logs(uint8_t argc, const Menu::arg *argv); - int8_t select_logs(uint8_t argc, const Menu::arg *argv); - bool print_log_menu(void); - - int8_t process_logs(uint8_t argc, const Menu::arg *argv); - int8_t main_menu_help(uint8_t, const Menu::arg*); - int8_t setup_mode(uint8_t argc, const Menu::arg *argv); - int8_t setup_factory(uint8_t argc, const Menu::arg *argv); - int8_t setup_set(uint8_t argc, const Menu::arg *argv); - int8_t setup_show(uint8_t argc, const Menu::arg *argv); - int8_t esc_calib(uint8_t argc, const Menu::arg *argv); - - int8_t test_mode(uint8_t argc, const Menu::arg *argv); - int8_t test_baro(uint8_t argc, const Menu::arg *argv); - int8_t test_compass(uint8_t argc, const Menu::arg *argv); - int8_t test_ins(uint8_t argc, const Menu::arg *argv); - int8_t test_optflow(uint8_t argc, const Menu::arg *argv); - int8_t test_relay(uint8_t argc, const Menu::arg *argv); - int8_t test_shell(uint8_t argc, const Menu::arg *argv); - int8_t test_rangefinder(uint8_t argc, const Menu::arg *argv); - - int8_t reboot_board(uint8_t argc, const Menu::arg *argv); }; -#define MENU_FUNC(func) FUNCTOR_BIND(&copter, &Copter::func, int8_t, uint8_t, const Menu::arg *) - extern const AP_HAL::HAL& hal; extern Copter copter; diff --git a/ArduCopter/GCS_Copter.h b/ArduCopter/GCS_Copter.h index cb3703262d..f6390de58f 100644 --- a/ArduCopter/GCS_Copter.h +++ b/ArduCopter/GCS_Copter.h @@ -24,7 +24,4 @@ private: GCS_MAVLINK_Copter _chan[MAVLINK_COMM_NUM_BUFFERS]; - bool cli_enabled() const override; - AP_HAL::BetterStream* cliSerial() override; - }; diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 86a8c0a8c1..f4eac8ff99 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -6,155 +6,6 @@ // Code to Write and Read packets from DataFlash log memory // Code to interact with the user to dump or erase logs -#if CLI_ENABLED == ENABLED - -// Creates a constant array of structs representing menu options -// and stores them in Flash memory, not RAM. -// User enters the string in the console to call the functions on the right. -// See class Menu in AP_Coommon for implementation details -static const struct Menu::command log_menu_commands[] = { - {"dump", MENU_FUNC(dump_log)}, - {"erase", MENU_FUNC(erase_logs)}, - {"enable", MENU_FUNC(select_logs)}, - {"disable", MENU_FUNC(select_logs)} -}; - -// A Macro to create the Menu -MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&copter, &Copter::print_log_menu, bool)); - -bool Copter::print_log_menu(void) -{ - cliSerial->printf("logs enabled: "); - - if (0 == g.log_bitmask) { - cliSerial->printf("none"); - }else{ - // Macro to make the following code a bit easier on the eye. - // Pass it the capitalised name of the log option, as defined - // in defines.h but without the LOG_ prefix. It will check for - // the bit being set and print the name of the log option to suit. -#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf(" %s", # _s) - PLOG(ATTITUDE_FAST); - PLOG(ATTITUDE_MED); - PLOG(GPS); - PLOG(PM); - PLOG(CTUN); - PLOG(NTUN); - PLOG(RCIN); - PLOG(IMU); - PLOG(CMD); - PLOG(CURRENT); - PLOG(RCOUT); - PLOG(OPTFLOW); - PLOG(COMPASS); - PLOG(CAMERA); - PLOG(PID); -#undef PLOG - } - - cliSerial->printf("\n"); - - DataFlash.ListAvailableLogs(cliSerial); - - return(true); -} - -int8_t Copter::dump_log(uint8_t argc, const Menu::arg *argv) -{ - int16_t dump_log_num; - uint16_t dump_log_start; - uint16_t dump_log_end; - - // check that the requested log number can be read - dump_log_num = argv[1].i; - - if (dump_log_num == -2) { - DataFlash.DumpPageInfo(cliSerial); - return(-1); - } else if (dump_log_num <= 0) { - cliSerial->printf("dumping all\n"); - Log_Read(0, 1, 0); - return(-1); - } else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) { - cliSerial->printf("bad log number\n"); - return(-1); - } - - DataFlash.get_log_boundaries(dump_log_num, dump_log_start, dump_log_end); - Log_Read((uint16_t)dump_log_num, dump_log_start, dump_log_end); - return (0); -} - -int8_t Copter::erase_logs(uint8_t argc, const Menu::arg *argv) -{ - DataFlash.EnableWrites(false); - do_erase_logs(); - DataFlash.EnableWrites(true); - return 0; -} - -int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv) -{ - uint16_t bits; - - if (argc != 2) { - cliSerial->printf("missing log type\n"); - return(-1); - } - - bits = 0; - - // Macro to make the following code a bit easier on the eye. - // Pass it the capitalised name of the log option, as defined - // in defines.h but without the LOG_ prefix. It will check for - // that name as the argument to the command, and set the bit in - // bits accordingly. - // - if (!strcasecmp(argv[1].str, "all")) { - bits = ~0; - } else { - #define TARG(_s) if (!strcasecmp(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s - TARG(ATTITUDE_FAST); - TARG(ATTITUDE_MED); - TARG(GPS); - TARG(PM); - TARG(CTUN); - TARG(NTUN); - TARG(RCIN); - TARG(IMU); - TARG(CMD); - TARG(CURRENT); - TARG(RCOUT); - TARG(OPTFLOW); - TARG(COMPASS); - TARG(CAMERA); - TARG(PID); - #undef TARG - } - - if (!strcasecmp(argv[0].str, "enable")) { - g.log_bitmask.set_and_save(g.log_bitmask | bits); - }else{ - g.log_bitmask.set_and_save(g.log_bitmask & ~bits); - } - - return(0); -} - -int8_t Copter::process_logs(uint8_t argc, const Menu::arg *argv) -{ - log_menu.run(); - return 0; -} -#endif // CLI_ENABLED - -void Copter::do_erase_logs(void) -{ - gcs().send_text(MAV_SEVERITY_INFO, "Erasing logs"); - DataFlash.EraseAll(); - gcs().send_text(MAV_SEVERITY_INFO, "Log erase complete"); -} - #if AUTOTUNE_ENABLED == ENABLED struct PACKED log_AutoTune { LOG_PACKET_HEADER; @@ -827,24 +678,6 @@ const struct LogStructure Copter::log_structure[] = { "THRO", "QBffffbbbb", "TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk" }, }; -#if CLI_ENABLED == ENABLED -// Read the DataFlash log memory -void Copter::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_page) -{ - cliSerial->printf("\n" FIRMWARE_STRING - "\nFree RAM: %u\n" - "\nFrame: %s\n", - (unsigned) hal.util->available_memory(), - get_frame_string()); - - cliSerial->printf("%s\n", HAL_BOARD_NAME); - - DataFlash.LogReadProcess(list_entry, start_page, end_page, - FUNCTOR_BIND_MEMBER(&Copter::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t), - cliSerial); -} -#endif // CLI_ENABLED - void Copter::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by DataFlash @@ -861,22 +694,10 @@ void Copter::Log_Write_Vehicle_Startup_Messages() void Copter::log_init(void) { DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); - - gcs().reset_cli_timeout(); } #else // LOGGING_ENABLED -#if CLI_ENABLED == ENABLED -bool Copter::print_log_menu(void) { return true; } -int8_t Copter::dump_log(uint8_t argc, const Menu::arg *argv) { return 0; } -int8_t Copter::erase_logs(uint8_t argc, const Menu::arg *argv) { return 0; } -int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv) { return 0; } -int8_t Copter::process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } -void Copter::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page) {} -#endif // CLI_ENABLED == ENABLED - -void Copter::do_erase_logs(void) {} void Copter::Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, \ float meas_min, float meas_max, float new_gain_rp, \ float new_gain_rd, float new_gain_sp, float new_ddt) {} diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 35abf63d4c..0a6690f475 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -58,15 +58,6 @@ const AP_Param::Info Copter::var_info[] = { // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), -#if CLI_ENABLED == ENABLED - // @Param: CLI_ENABLED - // @DisplayName: CLI Enable - // @Description: This enables/disables the checking for three carriage returns on telemetry links on startup to enter the diagnostics command line interface - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - GSCALAR(cli_enabled, "CLI_ENABLED", 0), -#endif - // @Param: PILOT_THR_FILT // @DisplayName: Throttle filter cutoff // @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable @@ -1064,7 +1055,7 @@ const AP_Param::ConversionInfo conversion_table[] = { void Copter::load_parameters(void) { if (!AP_Param::check_var_info()) { - cliSerial->printf("Bad var table\n"); + hal.console->printf("Bad var table\n"); AP_HAL::panic("Bad var table"); } @@ -1076,19 +1067,19 @@ void Copter::load_parameters(void) g.format_version != Parameters::k_format_version) { // erase all parameters - cliSerial->printf("Firmware change: erasing EEPROM...\n"); + hal.console->printf("Firmware change: erasing EEPROM...\n"); AP_Param::erase_all(); // save the current format version g.format_version.set_and_save(Parameters::k_format_version); - cliSerial->printf("done.\n"); + hal.console->printf("done.\n"); } uint32_t before = micros(); // Load all auto-loaded EEPROM variables AP_Param::load_all(false); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); - cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before)); + hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER); diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 24d4b62fb9..039d173b92 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -132,7 +132,7 @@ public: k_param_optflow, k_param_dcmcheck_thresh, // deprecated - remove k_param_log_bitmask, - k_param_cli_enabled, + k_param_cli_enabled_old, // deprecated - remove k_param_throttle_filt, k_param_throttle_behavior, k_param_pilot_takeoff_alt, // 64 @@ -380,9 +380,6 @@ public: AP_Int16 sysid_this_mav; AP_Int16 sysid_my_gcs; AP_Int8 telem_delay; -#if CLI_ENABLED == ENABLED - AP_Int8 cli_enabled; -#endif AP_Float throttle_filt; AP_Int16 throttle_behavior; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index de18851e47..daf6f1398d 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -637,11 +637,6 @@ // Developer Items // -// use this to completely disable the CLI -#ifndef CLI_ENABLED - # define CLI_ENABLED ENABLED -#endif - //use this to completely disable FRSKY TELEM #ifndef FRSKY_TELEM_ENABLED # define FRSKY_TELEM_ENABLED ENABLED diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index f0040daa0b..0433fec921 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -424,70 +424,3 @@ void Copter::notify_flight_mode(control_mode_t mode) break; } } - -// -// print_flight_mode - prints flight mode to serial port. -// -void Copter::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) -{ - switch (mode) { - case STABILIZE: - port->printf("STABILIZE"); - break; - case ACRO: - port->printf("ACRO"); - break; - case ALT_HOLD: - port->printf("ALT_HOLD"); - break; - case AUTO: - port->printf("AUTO"); - break; - case GUIDED: - port->printf("GUIDED"); - break; - case LOITER: - port->printf("LOITER"); - break; - case RTL: - port->printf("RTL"); - break; - case CIRCLE: - port->printf("CIRCLE"); - break; - case LAND: - port->printf("LAND"); - break; - case DRIFT: - port->printf("DRIFT"); - break; - case SPORT: - port->printf("SPORT"); - break; - case FLIP: - port->printf("FLIP"); - break; - case AUTOTUNE: - port->printf("AUTOTUNE"); - break; - case POSHOLD: - port->printf("POSHOLD"); - break; - case BRAKE: - port->printf("BRAKE"); - break; - case THROW: - port->printf("THROW"); - break; - case AVOID_ADSB: - port->printf("AVOID_ADSB"); - break; - case GUIDED_NOGPS: - port->printf("GUIDED_NOGPS"); - break; - default: - port->printf("Mode(%u)", (unsigned)mode); - break; - } -} - diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 2fea7d5957..bc603c5b08 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -106,7 +106,7 @@ void Copter::init_compass() if (!compass.init() || !compass.read()) { // make sure we don't pass a broken compass to DCM - cliSerial->printf("COMPASS INIT ERROR\n"); + hal.console->printf("COMPASS INIT ERROR\n"); Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE); return; } diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp index 56761bb7c4..6d5a546459 100644 --- a/ArduCopter/setup.cpp +++ b/ArduCopter/setup.cpp @@ -1,425 +1,15 @@ #include "Copter.h" -#if CLI_ENABLED == ENABLED - -#define PWM_CALIB_MIN 1000 -#define PWM_CALIB_MAX 2000 -#define PWM_HIGHEST_MAX 2200 -#define PWM_LOWEST_MAX 1200 -#define PWM_HIGHEST_MIN 1800 -#define PWM_LOWEST_MIN 800 - -// Command/function table for the setup menu -static const struct Menu::command setup_menu_commands[] = { - {"reset", MENU_FUNC(setup_factory)}, - {"show", MENU_FUNC(setup_show)}, - {"set", MENU_FUNC(setup_set)}, - {"esc_calib", MENU_FUNC(esc_calib)}, -}; - -// Create the setup menu object. -MENU(setup_menu, "setup", setup_menu_commands); - -// Called from the top-level menu to run the setup menu. -int8_t Copter::setup_mode(uint8_t argc, const Menu::arg *argv) -{ - // Give the user some guidance - cliSerial->printf("Setup Mode\n\n\n"); - - // Run the setup menu. When the menu exits, we will return to the main menu. - setup_menu.run(); - return 0; -} - -// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults). -// Called by the setup menu 'factoryreset' command. -int8_t Copter::setup_factory(uint8_t argc, const Menu::arg *argv) -{ - int16_t c; - - cliSerial->printf("\n'Y' = factory reset, any other key to abort:\n"); - - do { - c = cliSerial->read(); - } while (-1 == c); - - if (('y' != c) && ('Y' != c)) - return(-1); - - AP_Param::erase_all(); - cliSerial->printf("\nReboot board"); - - delay(1000); - - for (;; ) { - } - // note, cannot actually return here - return(0); -} - -//Set a parameter to a specified value. It will cast the value to the current type of the -//parameter and make sure it fits in case of INT8 and INT16 -int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv) -{ - int8_t value_int8; - int16_t value_int16; - - AP_Param *param; - enum ap_var_type p_type; - - if(argc!=3) - { - cliSerial->printf("Invalid command. Usage: set \n"); - return 0; - } - - param = AP_Param::find(argv[1].str, &p_type); - if(!param) - { - cliSerial->printf("Param not found: %s\n", argv[1].str); - return 0; - } - - const char *strType = "Value out of range for type"; - switch(p_type) - { - case AP_PARAM_INT8: - value_int8 = (int8_t)(argv[2].i); - if(argv[2].i!=value_int8) - { - cliSerial->printf("%s INT8\n", strType); - return 0; - } - ((AP_Int8*)param)->set_and_save(value_int8); - break; - case AP_PARAM_INT16: - value_int16 = (int16_t)(argv[2].i); - if(argv[2].i!=value_int16) - { - cliSerial->printf("%s INT16\n", strType); - return 0; - } - ((AP_Int16*)param)->set_and_save(value_int16); - break; - - //int32 and float don't need bounds checking, just use the value provoded by Menu::arg - case AP_PARAM_INT32: - ((AP_Int32*)param)->set_and_save(argv[2].i); - break; - case AP_PARAM_FLOAT: - ((AP_Float*)param)->set_and_save(argv[2].f); - break; - default: - cliSerial->printf("Cannot set parameter of type %d.\n", p_type); - break; - } - - return 0; -} - -// Print the current configuration. -// Called by the setup menu 'show' command. -int8_t Copter::setup_show(uint8_t argc, const Menu::arg *argv) -{ - AP_Param *param; - ap_var_type type; - - //If a parameter name is given as an argument to show, print only that parameter - if(argc>=2) - { - - param=AP_Param::find(argv[1].str, &type); - - if(!param) - { - cliSerial->printf("Parameter not found: '%s'\n", argv[1].str); - return 0; - } - AP_Param::show(param, argv[1].str, type, cliSerial); - return 0; - } - - // clear the area - print_blanks(8); - - report_version(); - report_radio(); - report_frame(); - report_batt_monitor(); - report_flight_modes(); - report_ins(); - report_compass(); - report_optflow(); - - AP_Param::show_all(cliSerial); - - return(0); -} - -int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv) -{ - - - char c; - unsigned max_channels = 0; - uint32_t set_mask = 0; - - uint16_t pwm_high = PWM_CALIB_MAX; - uint16_t pwm_low = PWM_CALIB_MIN; - - - if (argc < 2) { - cliSerial->printf("Pls provide Channel Mask\n" - "\tusage: esc_calib 1010 - enables calibration for 2nd and 4th Motor\n"); - return(0); - } - - - - set_mask = strtol (argv[1].str, nullptr, 2); - if (set_mask == 0) - cliSerial->printf("no channels chosen"); - //cliSerial->printf("\n%d\n",set_mask); - set_mask<<=1; - /* wait 50 ms */ - hal.scheduler->delay(50); - - - cliSerial->printf("\nATTENTION, please remove or fix propellers before starting calibration!\n" - "\n" - "Make sure\n" - "\t - that the ESCs are not powered\n" - "\t - that safety is off\n" - "\t - that the controllers are stopped\n" - "\n" - "Do you want to start calibration now: y or n?\n"); - - /* wait for user input */ - const char *strEscCalib = "ESC calibration"; - while (1) { - c= cliSerial->read(); - if (c == 'y' || c == 'Y') { - - break; - - } else if (c == 0x03 || c == 0x63 || c == 'q') { - cliSerial->printf("%s exited\n", strEscCalib); - return(0); - - } else if (c == 'n' || c == 'N') { - cliSerial->printf("%s aborted\n", strEscCalib); - return(0); - - } - - /* rate limit to ~ 20 Hz */ - hal.scheduler->delay(50); - } - - - /* get number of channels available on the device */ - max_channels = AP_MOTORS_MAX_NUM_MOTORS; - - /* tell IO/FMU that the system is armed (it will output values if safety is off) */ - motors->armed(true); - - - cliSerial->printf("Outputs armed\n"); - - - /* wait for user confirmation */ - cliSerial->printf("\nHigh PWM set: %d\n" - "\n" - "Connect battery now and hit c+ENTER after the ESCs confirm the first calibration step\n" - "\n", pwm_high); - - while (1) { - /* set max PWM */ - for (unsigned i = 0; i < max_channels; i++) { - - if (set_mask & 1<output_test(i, pwm_high); - } - } - c = cliSerial->read(); - - if (c == 'c') { - break; - - } else if (c == 0x03 || c == 'q') { - cliSerial->printf("%s exited\n", strEscCalib); - return(0); - } - - /* rate limit to ~ 20 Hz */ - hal.scheduler->delay(50); - } - - cliSerial->printf("Low PWM set: %d\n" - "\n" - "Hit c+Enter when finished\n" - "\n", pwm_low); - - while (1) { - - /* set disarmed PWM */ - for (unsigned i = 0; i < max_channels; i++) { - if (set_mask & 1<output_test(i, pwm_low); - } - } - c = cliSerial->read(); - - if (c == 'c') { - - break; - - } else if (c == 0x03 || c == 'q') { - cliSerial->printf("%s exited\n", strEscCalib); - return(0); - } - - /* rate limit to ~ 20 Hz */ - hal.scheduler->delay(50); - } - - /* disarm */ - motors->armed(false); - - cliSerial->printf("Outputs disarmed\n"); - - cliSerial->printf("%s finished\n", strEscCalib); - - return(0); -} - - -/***************************************************************************/ -// CLI reports -/***************************************************************************/ - -void Copter::report_batt_monitor() -{ - cliSerial->printf("\nBatt Mon:\n"); - print_divider(); - if (battery.num_instances() == 0) { - print_enabled(false); - } else if (!battery.has_current()) { - cliSerial->printf("volts"); - } else { - cliSerial->printf("volts and cur"); - } - print_blanks(2); -} - -void Copter::report_frame() -{ - cliSerial->printf("Frame\n"); - print_divider(); - cliSerial->printf("%s\n", get_frame_string()); - - print_blanks(2); -} - -void Copter::report_radio() -{ - cliSerial->printf("Radio\n"); - print_divider(); - // radio - print_radio_values(); - print_blanks(2); -} - -void Copter::report_ins() -{ - cliSerial->printf("INS\n"); - print_divider(); - - print_gyro_offsets(); - print_accel_offsets_and_scaling(); - print_blanks(2); -} - -void Copter::report_flight_modes() -{ - cliSerial->printf("Flight modes\n"); - print_divider(); - - for(int16_t i = 0; i < 6; i++ ) { - print_switch(i, (control_mode_t)flight_modes[i].get(), BIT_IS_SET(g.simple_modes, i)); - } - print_blanks(2); -} - -void Copter::report_optflow() -{ - #if OPTFLOW == ENABLED - cliSerial->printf("OptFlow\n"); - print_divider(); - - print_enabled(optflow.enabled()); - - print_blanks(2); - #endif // OPTFLOW == ENABLED -} - -/***************************************************************************/ -// CLI utilities -/***************************************************************************/ - -void Copter::print_radio_values() -{ - for (uint8_t i=0; i<8; i++) { - RC_Channel *rc = RC_Channels::rc_channel(i); - cliSerial->printf("CH%u: %d | %d\n", (unsigned)i, rc->get_radio_min(), rc->get_radio_max()); - } -} - -void Copter::print_switch(uint8_t p, uint8_t m, bool b) -{ - cliSerial->printf("Pos %d:\t",p); - print_flight_mode(cliSerial, m); - cliSerial->printf(",\t\tSimple: "); - if(b) - cliSerial->printf("ON\n"); - else - cliSerial->printf("OFF\n"); -} - -void Copter::print_accel_offsets_and_scaling(void) -{ - const Vector3f &accel_offsets = ins.get_accel_offsets(); - const Vector3f &accel_scale = ins.get_accel_scale(); - cliSerial->printf("A_off: %4.2f, %4.2f, %4.2f\nA_scale: %4.2f, %4.2f, %4.2f\n", - (double)accel_offsets.x, // Pitch - (double)accel_offsets.y, // Roll - (double)accel_offsets.z, // YAW - (double)accel_scale.x, // Pitch - (double)accel_scale.y, // Roll - (double)accel_scale.z); // YAW -} - -void Copter::print_gyro_offsets(void) -{ - const Vector3f &gyro_offsets = ins.get_gyro_offsets(); - cliSerial->printf("G_off: %4.2f, %4.2f, %4.2f\n", - (double)gyro_offsets.x, - (double)gyro_offsets.y, - (double)gyro_offsets.z); -} - -#endif // CLI_ENABLED - // report_compass - displays compass information. Also called by compassmot.pde void Copter::report_compass() { - cliSerial->printf("Compass\n"); + hal.console->printf("Compass\n"); print_divider(); print_enabled(g.compass_enabled); // mag declination - cliSerial->printf("Mag Dec: %4.4f\n", + hal.console->printf("Mag Dec: %4.4f\n", (double)degrees(compass.get_declination())); // mag offsets @@ -427,7 +17,7 @@ void Copter::report_compass() for (uint8_t i=0; iprintf("Mag%d off: %4.4f, %4.4f, %4.4f\n", + hal.console->printf("Mag%d off: %4.4f, %4.4f, %4.4f\n", (int)i, (double)offsets.x, (double)offsets.y, @@ -435,20 +25,20 @@ void Copter::report_compass() } // motor compensation - cliSerial->printf("Motor Comp: "); + hal.console->printf("Motor Comp: "); if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) { - cliSerial->printf("Off\n"); + hal.console->printf("Off\n"); }else{ if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) { - cliSerial->printf("Throttle"); + hal.console->printf("Throttle"); } if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) { - cliSerial->printf("Current"); + hal.console->printf("Current"); } Vector3f motor_compensation; for (uint8_t i=0; iprintf("\nComMot%d: %4.2f, %4.2f, %4.2f\n", + hal.console->printf("\nComMot%d: %4.2f, %4.2f, %4.2f\n", (int)i, (double)motor_compensation.x, (double)motor_compensation.y, @@ -462,30 +52,30 @@ void Copter::print_blanks(int16_t num) { while(num > 0) { num--; - cliSerial->printf("\n"); + hal.console->printf("\n"); } } void Copter::print_divider(void) { for (int i = 0; i < 40; i++) { - cliSerial->printf("-"); + hal.console->printf("-"); } - cliSerial->printf("\n"); + hal.console->printf("\n"); } void Copter::print_enabled(bool b) { if(b) - cliSerial->printf("en"); + hal.console->printf("en"); else - cliSerial->printf("dis"); - cliSerial->printf("abled\n"); + hal.console->printf("dis"); + hal.console->printf("abled\n"); } void Copter::report_version() { - cliSerial->printf("FW Ver: %d\n",(int)(g.k_format_version)); + hal.console->printf("FW Ver: %d\n",(int)(g.k_format_version)); print_divider(); print_blanks(2); } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index cbbd25faf3..69f70021e7 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -8,66 +8,6 @@ * *****************************************************************************/ -#if CLI_ENABLED == ENABLED - -// This is the help function -int8_t Copter::main_menu_help(uint8_t argc, const Menu::arg *argv) -{ - cliSerial->printf("Commands:\n" - " logs\n" - " setup\n" - " test\n" - " reboot\n" - "\n"); - return(0); -} - -// Command/function table for the top-level menu. -const struct Menu::command main_menu_commands[] = { -// command function called -// ======= =============== - {"logs", MENU_FUNC(process_logs)}, - {"setup", MENU_FUNC(setup_mode)}, - {"test", MENU_FUNC(test_mode)}, - {"reboot", MENU_FUNC(reboot_board)}, - {"help", MENU_FUNC(main_menu_help)}, -}; - -// Create the top-level menu object. -MENU(main_menu, THISFIRMWARE, main_menu_commands); - -int8_t Copter::reboot_board(uint8_t argc, const Menu::arg *argv) -{ - hal.scheduler->reboot(false); - return 0; -} - -// the user wants the CLI. It never exits -void Copter::run_cli(AP_HAL::UARTDriver *port) -{ - cliSerial = port; - Menu::set_port(port); - port->set_blocking_writes(true); - - // disable the mavlink delay callback - hal.scheduler->register_delay_callback(nullptr, 5); - - // disable main_loop failsafe - failsafe_disable(); - - // cut the engines - if(motors->armed()) { - motors->armed(false); - motors->output(); - } - - while (1) { - main_menu.run(); - } -} - -#endif // CLI_ENABLED - static void mavlink_delay_cb_static() { copter.mavlink_delay_cb(); @@ -96,9 +36,9 @@ void Copter::init_ardupilot() // init vehicle capabilties init_capabilities(); - cliSerial->printf("\n\nInit " FIRMWARE_STRING - "\n\nFree RAM: %u\n", - (unsigned)hal.util->available_memory()); + hal.console->printf("\n\nInit " FIRMWARE_STRING + "\n\nFree RAM: %u\n", + (unsigned)hal.util->available_memory()); // // Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function) @@ -123,13 +63,6 @@ void Copter::init_ardupilot() gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0); -#if CLI_ENABLED == ENABLED - // specify callback function for CLI menu system - if (g.cli_enabled) { - gcs().set_run_cli_func(FUNCTOR_BIND_MEMBER(&Copter::run_cli, void, AP_HAL::UARTDriver *)); - } -#endif - // Register mavlink_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5); @@ -257,10 +190,6 @@ void Copter::init_ardupilot() USERHOOK_INIT #endif -#if CLI_ENABLED == ENABLED - gcs().handle_interactive_setup(); -#endif // CLI_ENABLED - #if HIL_MODE != HIL_MODE_DISABLED while (barometer.get_last_update() == 0) { // the barometer begins updating when we get the first @@ -329,7 +258,7 @@ void Copter::init_ardupilot() // disable safety if requested BoardConfig.init_safety(); - cliSerial->printf("\nReady to FLY "); + hal.console->printf("\nReady to FLY "); // flag that initialisation has completed ap.initialised = true; diff --git a/ArduCopter/test.cpp b/ArduCopter/test.cpp deleted file mode 100644 index 784d27f8b0..0000000000 --- a/ArduCopter/test.cpp +++ /dev/null @@ -1,277 +0,0 @@ -#include "Copter.h" - -#if CLI_ENABLED == ENABLED - -// Creates a constant array of structs representing menu options -// and stores them in Flash memory, not RAM. -// User enters the string in the console to call the functions on the right. -// See class Menu in AP_Coommon for implementation details -static const struct Menu::command test_menu_commands[] = { -#if HIL_MODE == HIL_MODE_DISABLED - {"baro", MENU_FUNC(test_baro)}, -#endif - {"compass", MENU_FUNC(test_compass)}, - {"ins", MENU_FUNC(test_ins)}, - {"optflow", MENU_FUNC(test_optflow)}, - {"relay", MENU_FUNC(test_relay)}, -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN - {"shell", MENU_FUNC(test_shell)}, -#endif -#if HIL_MODE == HIL_MODE_DISABLED - {"rangefinder", MENU_FUNC(test_rangefinder)}, -#endif -}; - -// A Macro to create the Menu -MENU(test_menu, "test", test_menu_commands); - -int8_t Copter::test_mode(uint8_t argc, const Menu::arg *argv) -{ - test_menu.run(); - return 0; -} - -#if HIL_MODE == HIL_MODE_DISABLED -int8_t Copter::test_baro(uint8_t argc, const Menu::arg *argv) -{ - print_hit_enter(); - init_barometer(true); - - while(1) { - delay(100); - read_barometer(); - - if (!barometer.healthy()) { - cliSerial->printf("not healthy\n"); - } else { - cliSerial->printf("Alt: %0.2fm, Raw: %f Temperature: %.1f\n", - (double)(baro_alt / 100.0f), - (double)barometer.get_pressure(), - (double)barometer.get_temperature()); - } - if(cliSerial->available() > 0) { - return (0); - } - } - return 0; -} -#endif - -int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv) -{ - uint8_t delta_ms_fast_loop; - uint8_t medium_loopCounter = 0; - - if (!g.compass_enabled) { - cliSerial->printf("Compass: "); - print_enabled(false); - return (0); - } - - if (!compass.init()) { - cliSerial->printf("Compass initialisation failed!\n"); - return 0; - } - - ahrs.init(); - ahrs.set_fly_forward(true); - ahrs.set_compass(&compass); -#if OPTFLOW == ENABLED - ahrs.set_optflow(&optflow); -#endif - report_compass(); - - // we need the AHRS initialised for this test - ins.init(scheduler.get_loop_rate_hz()); - ahrs.reset(); - int16_t counter = 0; - float heading = 0; - - print_hit_enter(); - - while(1) { - delay(20); - if (millis() - fast_loopTimer > 19) { - delta_ms_fast_loop = millis() - fast_loopTimer; - G_Dt = (float)delta_ms_fast_loop / 1000.0f; // used by DCM integrator - fast_loopTimer = millis(); - - // INS - // --- - ahrs.update(); - - medium_loopCounter++; - if(medium_loopCounter == 5) { - if (compass.read()) { - // Calculate heading - const Matrix3f &m = ahrs.get_rotation_body_to_ned(); - heading = compass.calculate_heading(m); - compass.learn_offsets(); - } - medium_loopCounter = 0; - } - - counter++; - if (counter>20) { - if (compass.healthy()) { - const Vector3f &mag_ofs = compass.get_offsets(); - const Vector3f &mag = compass.get_field(); - cliSerial->printf("Heading: %d, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n", - (int)(wrap_360_cd(ToDeg(heading) * 100)) /100, - (double)mag.x, - (double)mag.y, - (double)mag.z, - (double)mag_ofs.x, - (double)mag_ofs.y, - (double)mag_ofs.z); - } else { - cliSerial->printf("compass not healthy\n"); - } - counter=0; - } - } - if (cliSerial->available() > 0) { - break; - } - } - - // save offsets. This allows you to get sane offset values using - // the CLI before you go flying. - cliSerial->printf("saving offsets\n"); - compass.save_offsets(); - return (0); -} - -int8_t Copter::test_ins(uint8_t argc, const Menu::arg *argv) -{ - Vector3f gyro, accel; - print_hit_enter(); - cliSerial->printf("INS\n"); - delay(1000); - - ahrs.init(); - ins.init(scheduler.get_loop_rate_hz()); - cliSerial->printf("...done\n"); - - delay(50); - - while(1) { - ins.update(); - gyro = ins.get_gyro(); - accel = ins.get_accel(); - - float test = accel.length() / GRAVITY_MSS; - - cliSerial->printf("a %7.4f %7.4f %7.4f g %7.4f %7.4f %7.4f t %7.4f \n", - (double)accel.x, (double)accel.y, (double)accel.z, - (double)gyro.x, (double)gyro.y, (double)gyro.z, - (double)test); - - delay(40); - if(cliSerial->available() > 0) { - return (0); - } - } -} - -int8_t Copter::test_optflow(uint8_t argc, const Menu::arg *argv) -{ -#if OPTFLOW == ENABLED - if(optflow.enabled()) { - cliSerial->printf("dev id: %d\t",(int)optflow.device_id()); - print_hit_enter(); - - while(1) { - delay(200); - optflow.update(); - const Vector2f& flowRate = optflow.flowRate(); - cliSerial->printf("flowX : %7.4f\t flowY : %7.4f\t flow qual : %d\n", - (double)flowRate.x, - (double)flowRate.y, - (int)optflow.quality()); - - if(cliSerial->available() > 0) { - return (0); - } - } - } else { - cliSerial->printf("OptFlow: "); - print_enabled(false); - } - return (0); -#else - return (0); -#endif // OPTFLOW == ENABLED -} - -int8_t Copter::test_relay(uint8_t argc, const Menu::arg *argv) -{ - print_hit_enter(); - delay(1000); - - while(1) { - cliSerial->printf("Relay on\n"); - relay.on(0); - delay(3000); - if(cliSerial->available() > 0) { - return (0); - } - - cliSerial->printf("Relay off\n"); - relay.off(0); - delay(3000); - if(cliSerial->available() > 0) { - return (0); - } - } -} - -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN -/* - * run a debug shell - */ -int8_t Copter::test_shell(uint8_t argc, const Menu::arg *argv) -{ - hal.util->run_debug_shell(cliSerial); - return 0; -} -#endif - -#if HIL_MODE == HIL_MODE_DISABLED -/* - * test the rangefinders - */ -int8_t Copter::test_rangefinder(uint8_t argc, const Menu::arg *argv) -{ -#if RANGEFINDER_ENABLED == ENABLED - rangefinder.init(); - - cliSerial->printf("RangeFinder: %d devices detected\n", rangefinder.num_sensors()); - - print_hit_enter(); - while(1) { - delay(100); - rangefinder.update(); - - for (uint8_t i=0; iprintf("Dev%d: status %d distance_cm %d\n", - (int)i, - (int)rangefinder.status(i), - (int)rangefinder.distance_cm(i)); - } - - if(cliSerial->available() > 0) { - return (0); - } - } -#endif - return (0); -} -#endif - -void Copter::print_hit_enter() -{ - cliSerial->printf("Hit Enter to exit.\n\n"); -} - -#endif // CLI_ENABLED diff --git a/ArduPlane/setup.cpp b/ArduPlane/setup.cpp deleted file mode 100644 index 8199a18c25..0000000000 --- a/ArduPlane/setup.cpp +++ /dev/null @@ -1,79 +0,0 @@ -#include "Plane.h" - -#if CLI_ENABLED == ENABLED - -// Command/function table for the setup menu -static const struct Menu::command setup_menu_commands[] = { - // command function called - // ======= =============== - {"reset", MENU_FUNC(setup_factory)}, - {"erase", MENU_FUNC(setup_erase)} -}; - -// Create the setup menu object. -MENU(setup_menu, "setup", setup_menu_commands); - -// Called from the top-level menu to run the setup menu. -int8_t Plane::setup_mode(uint8_t argc, const Menu::arg *argv) -{ - // Give the user some guidance - cliSerial->printf("Setup Mode\n" - "\n" - "IMPORTANT: if you have not previously set this system up, use the\n" - "'reset' command to initialize the EEPROM to sensible default values\n" - "and then the 'radio' command to configure for your radio.\n" - "\n"); - - // Run the setup menu. When the menu exits, we will return to the main menu. - setup_menu.run(); - return 0; -} - -// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults). -// Called by the setup menu 'factoryreset' command. -int8_t Plane::setup_factory(uint8_t argc, const Menu::arg *argv) -{ - int c; - - cliSerial->printf("\nType 'Y' and hit Enter to perform factory reset, any other key to abort: "); - - do { - c = cliSerial->read(); - } while (-1 == c); - - if (('y' != c) && ('Y' != c)) - return(-1); - AP_Param::erase_all(); - cliSerial->printf("\nFACTORY RESET complete - please reset board to continue"); - - for (;; ) { - } - // note, cannot actually return here - return(0); -} - - -int8_t Plane::setup_erase(uint8_t argc, const Menu::arg *argv) -{ - int c; - - cliSerial->printf("\nType 'Y' and hit Enter to erase all waypoint and parameter data, any other key to abort: "); - - do { - c = cliSerial->read(); - } while (-1 == c); - - if (('y' != c) && ('Y' != c)) - return(-1); - zero_eeprom(); - return 0; -} - -void Plane::zero_eeprom(void) -{ - cliSerial->printf("\nErasing EEPROM\n"); - StorageManager::erase(); - cliSerial->printf("done\n"); -} - -#endif // CLI_ENABLED diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp deleted file mode 100644 index ea982e5d57..0000000000 --- a/ArduPlane/test.cpp +++ /dev/null @@ -1,275 +0,0 @@ -#include "Plane.h" - -#if CLI_ENABLED == ENABLED - -// Creates a constant array of structs representing menu options -// and stores them in Flash memory, not RAM. -// User enters the string in the console to call the functions on the right. -// See class Menu in AP_Common for implementation details -static const struct Menu::command test_menu_commands[] = { - // Tests below here are for hardware sensors only present - // when real sensors are attached or they are emulated - {"gps", MENU_FUNC(test_gps)}, - {"ins", MENU_FUNC(test_ins)}, - {"airspeed", MENU_FUNC(test_airspeed)}, - {"airpressure", MENU_FUNC(test_pressure)}, - {"compass", MENU_FUNC(test_mag)}, - {"logging", MENU_FUNC(test_logging)}, -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN - {"shell", MENU_FUNC(test_shell)}, -#endif - -}; - -// A Macro to create the Menu -MENU(test_menu, "test", test_menu_commands); - -int8_t Plane::test_mode(uint8_t argc, const Menu::arg *argv) -{ - cliSerial->printf("Test Mode\n\n"); - test_menu.run(); - return 0; -} - -void Plane::print_hit_enter() -{ - cliSerial->printf("Hit Enter to exit.\n\n"); -} - -/* - * test the dataflash is working - */ -int8_t Plane::test_logging(uint8_t argc, const Menu::arg *argv) -{ - DataFlash.ShowDeviceInfo(cliSerial); - return 0; -} - -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN -/* - * run a debug shell - */ -int8_t Plane::test_shell(uint8_t argc, const Menu::arg *argv) -{ - hal.util->run_debug_shell(cliSerial); - return 0; -} -#endif - -//------------------------------------------------------------------------------------------- -// tests in this section are for real sensors or sensors that have been simulated - -int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv) -{ - print_hit_enter(); - hal.scheduler->delay(1000); - - uint32_t last_message_time_ms = 0; - while(1) { - hal.scheduler->delay(100); - - gps.update(); - - if (gps.last_message_time_ms() != last_message_time_ms) { - last_message_time_ms = gps.last_message_time_ms(); - const Location &loc = gps.location(); - cliSerial->printf("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n", - (long)loc.lat, - (long)loc.lng, - (long)loc.alt/100, - (int)gps.num_sats()); - } else { - cliSerial->printf("."); - } - if(cliSerial->available() > 0) { - return (0); - } - } -} - -int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv) -{ - //cliSerial->printf("Calibrating."); - ahrs.init(); - ahrs.set_fly_forward(true); - ahrs.set_wind_estimation(true); - - ins.init(scheduler.get_loop_rate_hz()); - ahrs.reset(); - - print_hit_enter(); - hal.scheduler->delay(1000); - - uint8_t counter = 0; - - while(1) { - hal.scheduler->delay(20); - if (micros() - perf.fast_loopTimer_us > 19000UL) { - perf.fast_loopTimer_us = micros(); - - // INS - // --- - ahrs.update(); - - if(g.compass_enabled) { - counter++; - if(counter == 5) { - compass.read(); - counter = 0; - } - } - - // We are using the INS - // --------------------- - Vector3f gyros = ins.get_gyro(); - Vector3f accels = ins.get_accel(); - cliSerial->printf("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n", - (int)ahrs.roll_sensor / 100, - (int)ahrs.pitch_sensor / 100, - (uint16_t)ahrs.yaw_sensor / 100, - (double)gyros.x, (double)gyros.y, (double)gyros.z, - (double)accels.x, (double)accels.y, (double)accels.z); - } - if(cliSerial->available() > 0) { - return (0); - } - } -} - - -int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv) -{ - if (!g.compass_enabled) { - cliSerial->printf("Compass: "); - print_enabled(false); - return (0); - } - - if (!compass.init()) { - cliSerial->printf("Compass initialisation failed!\n"); - return 0; - } - ahrs.init(); - ahrs.set_fly_forward(true); - ahrs.set_wind_estimation(true); - ahrs.set_compass(&compass); - - // we need the AHRS initialised for this test - ins.init(scheduler.get_loop_rate_hz()); - ahrs.reset(); - - uint16_t counter = 0; - float heading = 0; - - print_hit_enter(); - - while(1) { - hal.scheduler->delay(20); - if (micros() - perf.fast_loopTimer_us > 19000UL) { - perf.fast_loopTimer_us = micros(); - - // INS - // --- - ahrs.update(); - - if(counter % 5 == 0) { - if (compass.read()) { - // Calculate heading - const Matrix3f &m = ahrs.get_rotation_body_to_ned(); - heading = compass.calculate_heading(m); - compass.learn_offsets(); - } - } - - counter++; - if (counter>20) { - if (compass.healthy()) { - const Vector3f &mag_ofs = compass.get_offsets(); - const Vector3f &mag = compass.get_field(); - cliSerial->printf("Heading: %f, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n", - (double)((wrap_360_cd(ToDeg(heading) * 100)) /100), - (double)mag.x, (double)mag.y, (double)mag.z, - (double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z); - } else { - cliSerial->printf("compass not healthy\n"); - } - counter=0; - } - } - if (cliSerial->available() > 0) { - break; - } - } - - // save offsets. This allows you to get sane offset values using - // the CLI before you go flying. - cliSerial->printf("saving offsets\n"); - compass.save_offsets(); - return (0); -} - -//------------------------------------------------------------------------------------------- -// real sensors that have not been simulated yet go here - -int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv) -{ - if (!airspeed.enabled()) { - cliSerial->printf("airspeed: "); - print_enabled(false); - return (0); - }else{ - print_hit_enter(); - zero_airspeed(false); - cliSerial->printf("airspeed: "); - print_enabled(true); - - while(1) { - hal.scheduler->delay(20); - read_airspeed(); - cliSerial->printf("%.1f m/s\n", (double)airspeed.get_airspeed()); - - if(cliSerial->available() > 0) { - return (0); - } - } - } -} - - -int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv) -{ - cliSerial->printf("Uncalibrated relative airpressure\n"); - print_hit_enter(); - - init_barometer(true); - - while(1) { - hal.scheduler->delay(100); - barometer.update(); - - if (!barometer.healthy()) { - cliSerial->printf("not healthy\n"); - } else { - cliSerial->printf("Alt: %0.2fm, Raw: %f Temperature: %.1f\n", - (double)barometer.get_altitude(), - (double)barometer.get_pressure(), - (double)barometer.get_temperature()); - } - - if(cliSerial->available() > 0) { - return (0); - } - } -} - -void Plane::print_enabled(bool b) -{ - if (b) { - cliSerial->printf("en"); - } else { - cliSerial->printf("dis"); - } - cliSerial->printf("abled\n"); -} - -#endif // CLI_ENABLED