2010-08-28 13:07:33 -03:00
|
|
|
/*
|
|
|
|
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
|
2010-10-19 12:22:58 -03:00
|
|
|
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
|
|
|
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
|
|
|
Sandro Benigno, Chris Anderson
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
|
|
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 <http://www.gnu.org/licenses/>.
|
2010-10-19 12:22:58 -03:00
|
|
|
|
|
|
|
* ************************************************************** *
|
|
|
|
ChangeLog:
|
|
|
|
|
|
|
|
|
|
|
|
* ************************************************************** *
|
|
|
|
TODO:
|
|
|
|
|
|
|
|
|
|
|
|
* ************************************************************** */
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
|
|
// General Initialization for all APM electronics
|
|
|
|
void APM_Init() {
|
|
|
|
|
2010-10-18 15:24:46 -03:00
|
|
|
// 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)
|
2010-10-19 12:22:58 -03:00
|
|
|
|
2010-10-18 15:24:46 -03:00
|
|
|
// Because DDRE and DDRL Ports are not included to normal Arduino Libraries, we need to
|
|
|
|
// initialize them with a special command
|
2010-10-19 12:22:58 -03:00
|
|
|
APMPinMode(DDRE,7,INPUT); // DIP1, (PE7), Closest DIP to sliding SW2 switch
|
2010-10-18 15:24:46 -03:00
|
|
|
APMPinMode(DDRE,6,INPUT); // DIP2, (PE6)
|
|
|
|
APMPinMode(DDRL,6,INPUT); // DIP3, (PL6)
|
2010-10-19 12:22:58 -03:00
|
|
|
APMPinMode(DDRL,7,INPUT); // DIP4, (PL7), Furthest DIP from sliding SW2 switch
|
|
|
|
|
2010-10-18 05:26:08 -03:00
|
|
|
|
2010-10-19 12:22:58 -03:00
|
|
|
/* ********************************************************* */
|
|
|
|
/////////////////////////////////////////////////////////
|
2010-10-18 15:24:46 -03:00
|
|
|
// Normal Initialization sequence starts from here.
|
2010-12-20 23:23:03 -04:00
|
|
|
readUserConfig(); // Load user configurable items from EEPROM
|
2010-10-19 12:22:58 -03:00
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
APM_RC.Init(); // APM Radio initialization
|
2010-10-18 15:24:46 -03:00
|
|
|
|
2010-11-23 21:30:41 -04:00
|
|
|
#if AIRFRAME == QUAD
|
2010-10-13 13:48:09 -03:00
|
|
|
// 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);
|
2010-11-23 21:30:41 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AIRFRAME == HELI
|
|
|
|
// RC channels Initialization (heli servos)
|
|
|
|
APM_RC.OutputCh(0,CHANN_CENTER); // mid position
|
|
|
|
APM_RC.OutputCh(1,CHANN_CENTER);
|
|
|
|
APM_RC.OutputCh(2,CHANN_CENTER);
|
|
|
|
APM_RC.OutputCh(3,CHANN_CENTER);
|
|
|
|
#endif
|
2010-10-18 15:24:46 -03:00
|
|
|
// Make sure that Relay is switched off.
|
|
|
|
digitalWrite(RELAY,LOW);
|
|
|
|
|
|
|
|
// Wiggle LEDs while ESCs are rebooting
|
2010-10-13 13:48:09 -03:00
|
|
|
FullBlink(50,20);
|
2010-10-18 15:24:46 -03:00
|
|
|
|
2010-11-27 00:56:31 -04:00
|
|
|
adc.Init(); // APM ADC library initialization
|
2010-08-28 13:07:33 -03:00
|
|
|
DataFlash.Init(); // DataFlash log initialization
|
|
|
|
|
|
|
|
#ifdef IsGPS
|
|
|
|
GPS.Init(); // GPS Initialization
|
2010-10-18 15:24:46 -03:00
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
#ifdef IsNEWMTEK
|
|
|
|
delay(250);
|
2010-10-18 15:24:46 -03:00
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
// 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
|
2010-10-11 09:20:30 -03:00
|
|
|
Serial1.print("$PMTK220,200*2C\r\n"); // 5Hz update rate
|
|
|
|
delay(200);
|
2010-08-28 13:07:33 -03:00
|
|
|
Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n");
|
2010-10-18 15:24:46 -03:00
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
|
2010-12-08 08:34:02 -04:00
|
|
|
// 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);
|
2010-10-30 05:30:46 -03:00
|
|
|
|
|
|
|
// Is CLI mode active or not, if it is fire it up and never return.
|
2010-12-08 12:16:40 -04:00
|
|
|
if(!digitalRead(SW2)) {
|
2010-10-30 05:30:46 -03:00
|
|
|
RunCLI();
|
|
|
|
// Btw.. We never return from this....
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-10-19 13:07:51 -03:00
|
|
|
flightOrientation = SW_DIP1; // DIP1 off = we are in + mode, DIP1 on = we are in x mode
|
2010-12-20 23:23:03 -04:00
|
|
|
|
|
|
|
// readUserConfig moved to up to ensure min throttle is read from eeprom
|
|
|
|
//readUserConfig(); // Load user configurable items from EEPROM
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
|
|
// 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;
|
|
|
|
|
2010-11-23 21:30:41 -04:00
|
|
|
#if AIRFRAME == QUAD
|
2010-08-28 13:07:33 -03:00
|
|
|
// 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);
|
2010-11-23 21:30:41 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AIRFRAME == HELI
|
|
|
|
// RC channels Initialization (heli servos)
|
|
|
|
APM_RC.OutputCh(0,CHANN_CENTER); // mid position
|
|
|
|
APM_RC.OutputCh(1,CHANN_CENTER);
|
|
|
|
APM_RC.OutputCh(2,CHANN_CENTER);
|
|
|
|
APM_RC.OutputCh(3,CHANN_CENTER);
|
|
|
|
#endif
|
2010-08-28 13:07:33 -03:00
|
|
|
|
2010-11-22 09:53:13 -04:00
|
|
|
// Initialise Wire library used by Magnetometer and Barometer
|
|
|
|
Wire.begin();
|
|
|
|
|
2010-10-31 11:01:21 -03:00
|
|
|
#ifdef IsMAG
|
2010-10-19 12:22:58 -03:00
|
|
|
if (MAGNETOMETER == 1) {
|
2010-12-12 10:05:31 -04:00
|
|
|
AP_Compass.init(FALSE); // I2C initialization
|
|
|
|
AP_Compass.set_orientation(MAGORIENTATION);
|
|
|
|
AP_Compass.set_offsets(mag_offset_x, mag_offset_y, mag_offset_z);
|
|
|
|
AP_Compass.set_declination(ToRad(DECLINATION));
|
2010-10-19 12:22:58 -03:00
|
|
|
}
|
|
|
|
#endif
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
|
|
DataFlash.StartWrite(1); // Start a write session on page 1
|
|
|
|
|
2010-10-17 14:34:17 -03:00
|
|
|
// Proper Serial port/baud are defined on main .pde and then Arducopter.h with
|
2010-10-18 15:24:46 -03:00
|
|
|
// Choises of Xbee or normal serial port
|
2010-10-17 14:34:17 -03:00
|
|
|
SerBeg(SerBau);
|
2010-10-19 12:22:58 -03:00
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
// Check if we enable the DataFlash log Read Mode (switch)
|
|
|
|
// If we press switch 1 at startup we read the Dataflash eeprom
|
2010-10-30 05:30:46 -03:00
|
|
|
while (digitalRead(SW1)==0) // LEGACY remove soon by jp, 30-10-10
|
2010-08-28 13:07:33 -03:00
|
|
|
{
|
2010-10-18 15:24:46 -03:00
|
|
|
Serial.println("Entering Log Read Mode..."); // This will be obsole soon due moving to CLI system
|
2010-08-28 13:07:33 -03:00
|
|
|
Log_Read(1,1000);
|
|
|
|
delay(30000);
|
|
|
|
}
|
2010-10-18 15:24:46 -03:00
|
|
|
|
2010-10-11 18:54:42 -03:00
|
|
|
calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde)
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
|
|
// Neutro_yaw = APM_RC.InputCh(3); // Take yaw neutral radio value
|
|
|
|
#ifndef CONFIGURATOR
|
|
|
|
for(i=0;i<6;i++)
|
|
|
|
{
|
2010-12-26 00:30:55 -04:00
|
|
|
SerPri("AN[]:");
|
|
|
|
SerPrln(AN_OFFSET[i]);
|
2010-08-28 13:07:33 -03:00
|
|
|
}
|
2010-12-26 00:30:55 -04:00
|
|
|
SerPri("Yaw neutral value:");
|
|
|
|
SerPri(yaw_mid);
|
2010-08-28 13:07:33 -03:00
|
|
|
#endif
|
|
|
|
|
2010-10-11 09:20:30 -03:00
|
|
|
#ifdef UseBMP
|
2010-11-22 09:53:13 -04:00
|
|
|
APM_BMP085.Init(FALSE);
|
2010-10-11 09:20:30 -03:00
|
|
|
#endif
|
2010-08-28 13:07:33 -03:00
|
|
|
|
2010-12-22 09:38:54 -04:00
|
|
|
#ifdef IsRANGEFINDER
|
2010-12-31 19:58:34 -04:00
|
|
|
AP_RangeFinder_down.init(AN5); AP_RangeFinder_down.set_orientation(AP_RANGEFINDER_ORIENTATION_DOWN);
|
2010-12-26 00:30:55 -04:00
|
|
|
//AP_RangeFinder_frontRight.init(AN5); AP_RangeFinder_frontRight.set_orientation(AP_RANGEFINDER_ORIENTATION_FRONT_RIGHT);
|
|
|
|
//AP_RangeFinder_backRight.init(AN4); AP_RangeFinder_backRight.set_orientation(AP_RANGEFINDER_ORIENTATION_BACK_RIGHT);
|
|
|
|
//AP_RangeFinder_backLeft.init(AN3); AP_RangeFinder_backLeft.set_orientation(AP_RANGEFINDER_ORIENTATION_BACK_LEFT);
|
|
|
|
//AP_RangeFinder_frontLeft.init(AN2); AP_RangeFinder_frontLeft.set_orientation(AP_RANGEFINDER_ORIENTATION_FRONT_LEFT);
|
2010-12-22 09:38:54 -04:00
|
|
|
#endif
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
delay(1000);
|
|
|
|
|
|
|
|
DataFlash.StartWrite(1); // Start a write session on page 1
|
|
|
|
|
2010-11-23 21:30:41 -04:00
|
|
|
// initialise helicopter
|
|
|
|
#if AIRFRAME == HELI
|
|
|
|
heli_setup();
|
|
|
|
#endif
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
#ifdef IsAM
|
|
|
|
// Switch Left & Right lights on
|
|
|
|
digitalWrite(RI_LED, HIGH);
|
|
|
|
digitalWrite(LE_LED, HIGH);
|
|
|
|
#endif
|
2010-10-17 14:34:17 -03:00
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
}
|
2010-10-17 14:34:17 -03:00
|
|
|
|
2010-12-22 09:38:54 -04:00
|
|
|
|