void Copter::init_ardupilot() { if (!hal.gpio->usb_connected()) { // USB is not connected, this means UART0 may be a Xbee, with // its darned bricking problem. We can't write to it for at // least one second after powering up. Simplest solution for // now is to delay for 1 second. Something more elegant may be // added later delay(1000); } // initialise serial port serial_manager.init_console(); // init vehicle capabilties init_capabilities(); cliSerial->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) // report_version(); // load parameters from EEPROM load_parameters(); BoardConfig.init(); // initialise serial port serial_manager.init(); // init EPM cargo gripper #if EPM_ENABLED == ENABLED epm.init(); #endif // initialise notify system // disable external leds if epm is enabled because of pin conflict on the APM notify.init(true); // initialise battery monitor battery.init(); // Init RSSI rssi.init(); barometer.init(); // Register the mavlink service callback. This will run // anytime there are more than 5ms remaining in a call to // hal.scheduler->delay. hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5); // we start by assuming USB connected, as we initialed the serial // port with SERIAL0_BAUD. check_usb_mux() fixes this if need be. ap.usb_connected = true; check_usb_mux(); // init the GCS connected to the console gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console, 0); // init telemetry port gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0); // setup serial port for telem2 gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1); // setup serial port for fourth telemetry port (not used by default) gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2); #if FRSKY_TELEM_ENABLED == ENABLED // setup frsky frsky_telemetry.init(serial_manager); #endif // identify ourselves correctly with the ground station mavlink_system.sysid = g.sysid_this_mav; #if LOGGING_ENABLED == ENABLED log_init(); #endif GCS_MAVLINK::set_dataflash(&DataFlash); // update motor interlock state update_using_interlock(); #if FRAME_CONFIG == HELI_FRAME // trad heli specific initialisation heli_init(); #endif init_rc_in(); // sets up rc channels from radio init_rc_out(); // sets up motors and output to escs // initialise which outputs Servo and Relay events can use ServoRelayEvents.set_channel_mask(~motors.get_motor_mask()); relay.init(); /* * setup the 'main loop is dead' check. Note that this relies on * the RC library being initialised. */ hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000); // Do GPS init gps.init(&DataFlash, serial_manager); if(g.compass_enabled) init_compass(); #if OPTFLOW == ENABLED // make optflow available to AHRS ahrs.set_optflow(&optflow); #endif // init Location class Location_Class::set_ahrs(&ahrs); #if AP_TERRAIN_AVAILABLE && AC_TERRAIN Location_Class::set_terrain(&terrain); wp_nav.set_terrain(&terrain); #endif pos_control.set_dt(MAIN_LOOP_SECONDS); // init the optical flow sensor init_optflow(); #if MOUNT == ENABLED // initialise camera mount camera_mount.init(&DataFlash, serial_manager); #endif #if PRECISION_LANDING == ENABLED // initialise precision landing init_precland(); #endif #ifdef USERHOOK_INIT USERHOOK_INIT #endif #if CLI_ENABLED == ENABLED if (g.cli_enabled) { const char *msg = "\nPress ENTER 3 times to start interactive setup\n"; cliSerial->println(msg); if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) { gcs[1].get_uart()->println(msg); } if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) { gcs[2].get_uart()->println(msg); } } #endif // CLI_ENABLED #if HIL_MODE != HIL_MODE_DISABLED while (barometer.get_last_update() == 0) { // the barometer begins updating when we get the first // HIL_STATE message gcs_send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message"); delay(1000); } // set INS to HIL mode ins.set_hil_mode(); #endif // read Baro pressure at ground //----------------------------- init_barometer(true); // initialise sonar #if CONFIG_SONAR == ENABLED init_sonar(); #endif // initialise AP_RPM library rpm_sensor.init(); // initialise mission library mission.init(); // initialise the flight mode and aux switch // --------------------------- reset_control_switch(); init_aux_switches(); startup_INS_ground(); // set landed flags set_land_complete(true); set_land_complete_maybe(true); // we don't want writes to the serial port to cause us to pause // mid-flight, so set the serial ports non-blocking once we are // ready to fly serial_manager.set_blocking_writes_all(false); // enable CPU failsafe failsafe_enable(); ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_dataflash(&DataFlash); cliSerial->print("\nReady to FLY "); // flag that initialisation has completed ap.initialised = true; }
int8_t Rover::test_sonar(uint8_t argc, const Menu::arg *argv) { init_sonar(); delay(20); sonar.update(); if (sonar.status() == RangeFinder::RangeFinder_NotConnected) { cliSerial->println("WARNING: Sonar is not enabled"); } print_hit_enter(); float sonar_dist_cm_min = 0.0f; float sonar_dist_cm_max = 0.0f; float voltage_min=0.0f, voltage_max = 0.0f; float sonar2_dist_cm_min = 0.0f; float sonar2_dist_cm_max = 0.0f; float voltage2_min=0.0f, voltage2_max = 0.0f; uint32_t last_print = 0; while (true) { delay(20); sonar.update(); uint32_t now = millis(); float dist_cm = sonar.distance_cm(0); float voltage = sonar.voltage_mv(0); if (is_zero(sonar_dist_cm_min)) { sonar_dist_cm_min = dist_cm; voltage_min = voltage; } sonar_dist_cm_max = MAX(sonar_dist_cm_max, dist_cm); sonar_dist_cm_min = MIN(sonar_dist_cm_min, dist_cm); voltage_min = MIN(voltage_min, voltage); voltage_max = MAX(voltage_max, voltage); dist_cm = sonar.distance_cm(1); voltage = sonar.voltage_mv(1); if (is_zero(sonar2_dist_cm_min)) { sonar2_dist_cm_min = dist_cm; voltage2_min = voltage; } sonar2_dist_cm_max = MAX(sonar2_dist_cm_max, dist_cm); sonar2_dist_cm_min = MIN(sonar2_dist_cm_min, dist_cm); voltage2_min = MIN(voltage2_min, voltage); voltage2_max = MAX(voltage2_max, voltage); if (now - last_print >= 200) { cliSerial->printf("sonar1 dist=%.1f:%.1fcm volt1=%.2f:%.2f sonar2 dist=%.1f:%.1fcm volt2=%.2f:%.2f\n", (double)sonar_dist_cm_min, (double)sonar_dist_cm_max, (double)voltage_min, (double)voltage_max, (double)sonar2_dist_cm_min, (double)sonar2_dist_cm_max, (double)voltage2_min, (double)voltage2_max); voltage_min = voltage_max = 0.0f; voltage2_min = voltage2_max = 0.0f; sonar_dist_cm_min = sonar_dist_cm_max = 0.0f; sonar2_dist_cm_min = sonar2_dist_cm_max = 0.0f; last_print = now; } if (cliSerial->available() > 0) { break; } } return (0); }
void Rover::init_ardupilot() { // initialise console serial port serial_manager.init_console(); cliSerial->printf("\n\nInit " FIRMWARE_STRING "\n\nFree RAM: %u\n", hal.util->available_memory()); // // Check the EEPROM format version before loading any parameters from EEPROM. // load_parameters(); BoardConfig.init(); // initialise serial ports serial_manager.init(); ServoRelayEvents.set_channel_mask(0xFFF0); set_control_channels(); battery.init(); // keep a record of how many resets have happened. This can be // used to detect in-flight resets g.num_resets.set_and_save(g.num_resets+1); // init baro before we start the GCS, so that the CLI baro test works barometer.init(); // init the GCS gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console, 0); // we start by assuming USB connected, as we initialed the serial // port with SERIAL0_BAUD. check_usb_mux() fixes this if need be. usb_connected = true; check_usb_mux(); // setup serial port for telem1 gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0); // setup serial port for telem2 gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1); // setup serial port for fourth telemetry port (not used by default) gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2); // setup frsky telemetry #if FRSKY_TELEM_ENABLED == ENABLED frsky_telemetry.init(serial_manager); #endif mavlink_system.sysid = g.sysid_this_mav; #if LOGGING_ENABLED == ENABLED log_init(); #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); if (g.compass_enabled==true) { if (!compass.init()|| !compass.read()) { cliSerial->println("Compass initialisation failed!"); g.compass_enabled = false; } else { ahrs.set_compass(&compass); //compass.get_offsets(); // load offsets to account for airframe magnetic interference } } // initialise sonar init_sonar(); // and baro for EKF init_barometer(); // Do GPS init gps.init(&DataFlash, serial_manager); rc_override_active = hal.rcin->set_overrides(rc_override, 8); init_rc_in(); // sets up rc channels from radio init_rc_out(); // sets up the timer libs relay.init(); #if MOUNT == ENABLED // initialise camera mount camera_mount.init(serial_manager); #endif /* setup the 'main loop is dead' check. Note that this relies on the RC library being initialised. */ hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000); #if CLI_ENABLED == ENABLED // If the switch is in 'menu' mode, run the main menu. // // Since we can't be sure that the setup or test mode won't leave // the system in an odd state, we don't let the user exit the top // menu; they must reset in order to fly. // if (g.cli_enabled == 1) { const char *msg = "\nPress ENTER 3 times to start interactive setup\n"; cliSerial->println(msg); if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) { gcs[1].get_uart()->println(msg); } if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) { gcs[2].get_uart()->println(msg); } } #endif init_capabilities(); startup_ground(); set_mode((enum mode)g.initial_mode.get()); // set the correct flight mode // --------------------------- reset_control_switch(); }