/* www.ArduCopter.com - www.DIYDrones.com Copyright (c) 2010. All rights reserved. An Open Source Arduino based multicopter. File : System.pde Version : v1.0, Aug 27, 2010 Author(s): ArduCopter Team Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz, Jani Hirvinen, Ken McEwans, Roberto Navoni, Sandro Benigno, Chris Anderson This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . * ************************************************************** * ChangeLog: * ************************************************************** * TODO: * ************************************************************** */ // General Initialization for all APM electronics void APM_Init() { // Setup proper PIN modes for our switched, LEDs, Relays etc on IMU Board pinMode(LED_Yellow,OUTPUT); // Yellow LED A (PC1) pinMode(LED_Red,OUTPUT); // Red LED B (PC2) pinMode(LED_Green,OUTPUT); // Green LED C (PC0) pinMode(RELAY,OUTPUT); // Relay output (PL2) pinMode(SW1,INPUT); // Switch SW1 (PG0) pinMode(SW2,INPUT); // Switch SW2 (PG1) // Because DDRE and DDRL Ports are not included to normal Arduino Libraries, we need to // initialize them with a special command APMPinMode(DDRE,7,INPUT); // DIP1, (PE7), Closest DIP to sliding SW2 switch APMPinMode(DDRE,6,INPUT); // DIP2, (PE6) APMPinMode(DDRL,6,INPUT); // DIP3, (PL6) APMPinMode(DDRL,7,INPUT); // DIP4, (PL7), Furthest DIP from sliding SW2 switch /* ********************************************************* */ ///////////////////////////////////////////////////////// // Normal Initialization sequence starts from here. APM_RC.Init(); // APM Radio initialization // RC channels Initialization (Quad motors) APM_RC.OutputCh(0,MIN_THROTTLE); // Motors stoped APM_RC.OutputCh(1,MIN_THROTTLE); APM_RC.OutputCh(2,MIN_THROTTLE); APM_RC.OutputCh(3,MIN_THROTTLE); // Make sure that Relay is switched off. digitalWrite(RELAY,LOW); // Wiggle LEDs while ESCs are rebooting FullBlink(50,20); APM_ADC.Init(); // APM ADC library initialization DataFlash.Init(); // DataFlash log initialization #ifdef IsGPS GPS.Init(); // GPS Initialization #ifdef IsNEWMTEK delay(250); // DIY Drones MTEK GPS needs binary sentences activated if you upgraded to latest firmware. // If your GPS shows solid blue but LED C (Red) does not go on, your GPS is on NMEA mode Serial1.print("$PMTK220,200*2C\r\n"); // 5Hz update rate delay(200); Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n"); #endif #endif // Is CLI mode active or not, if it is fire it up and never return. if(digitalRead(SW2)) { RunCLI(); // Btw.. We never return from this.... } // Read DIP Switches and other important values. DIP switches needs special functions to // read due they are not defined as normal pins like other GPIO's are. SW_DIP1 = APMPinRead(PINE, 7); SW_DIP2 = APMPinRead(PINE, 6); SW_DIP3 = APMPinRead(PINL, 6); SW_DIP4 = APMPinRead(PINL, 7); /* Works, tested 18-10-10 JP if(SW_DIP1) { SerPrln("+ mode"); } else { SerPrln("x mode"); } */ flightOrientation = SW_DIP1; // DIP1 off = we are in + mode, DIP1 on = we are in x mode readUserConfig(); // Load user configurable items from EEPROM // Safety measure for Channel mids if(roll_mid < 1400 || roll_mid > 1600) roll_mid = 1500; if(pitch_mid < 1400 || pitch_mid > 1600) pitch_mid = 1500; if(yaw_mid < 1400 || yaw_mid > 1600) yaw_mid = 1500; // RC channels Initialization (Quad motors) APM_RC.OutputCh(0,MIN_THROTTLE); // Motors stoped APM_RC.OutputCh(1,MIN_THROTTLE); APM_RC.OutputCh(2,MIN_THROTTLE); APM_RC.OutputCh(3,MIN_THROTTLE); #ifdef IsMAG if (MAGNETOMETER == 1) { APM_Compass.Init(); // I2C initialization APM_Compass.SetOrientation(MAGORIENTATION); APM_Compass.SetOffsets(MAGOFFSET); APM_Compass.SetDeclination(ToRad(DECLINATION)); } #endif DataFlash.StartWrite(1); // Start a write session on page 1 //Serial.begin(115200); // Old mode serial begin, remove soon, by jp/17-10-10 //Serial.println("ArduCopter Quadcopter v1.0"); // Proper Serial port/baud are defined on main .pde and then Arducopter.h with // Choises of Xbee or normal serial port SerBeg(SerBau); // Check if we enable the DataFlash log Read Mode (switch) // If we press switch 1 at startup we read the Dataflash eeprom while (digitalRead(SW1)==0) // LEGACY remove soon by jp, 30-10-10 { Serial.println("Entering Log Read Mode..."); // This will be obsole soon due moving to CLI system Log_Read(1,1000); delay(30000); } calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde) // Neutro_yaw = APM_RC.InputCh(3); // Take yaw neutral radio value #ifndef CONFIGURATOR for(i=0;i<6;i++) { Serial.print("AN[]:"); Serial.println(AN_OFFSET[i]); } Serial.print("Yaw neutral value:"); // Serial.println(Neutro_yaw); Serial.print(yaw_mid); #endif #ifdef UseBMP APM_BMP085.Init(); #endif delay(1000); DataFlash.StartWrite(1); // Start a write session on page 1 //timer = millis(); //tlmTimer = millis(); #ifdef IsAM // Switch Left & Right lights on digitalWrite(RI_LED, HIGH); digitalWrite(LE_LED, HIGH); #endif }