2010-10-18 15:24:46 -03:00
|
|
|
/*
|
|
|
|
www.ArduCopter.com - www.DIYDrones.com
|
|
|
|
Copyright (c) 2010. All rights reserved.
|
|
|
|
An Open Source Arduino based multicopter.
|
|
|
|
|
|
|
|
File : CLI.pde
|
|
|
|
Version : v1.0, Oct 18, 2010
|
|
|
|
Author(s): ArduCopter Team
|
|
|
|
Jani Hirvinen, Jose Julio, Jordi Muñoz,
|
2010-10-30 05:30:46 -03:00
|
|
|
Ken McEwans, Roberto Navoni, Sandro Benigno, Chris Anderson, Randy McEvans
|
2010-10-18 15:24:46 -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/>.
|
|
|
|
|
|
|
|
* ************************************************************** *
|
|
|
|
ChangeLog:
|
2010-10-19 12:22:58 -03:00
|
|
|
- 19-10-10 Initial CLI
|
2010-10-18 15:24:46 -03:00
|
|
|
|
|
|
|
* ************************************************************** *
|
|
|
|
TODO:
|
2010-10-19 12:22:58 -03:00
|
|
|
- Full menu systems, debug, settings
|
2010-10-18 15:24:46 -03:00
|
|
|
|
|
|
|
* ************************************************************** */
|
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
|
2010-10-19 12:22:58 -03:00
|
|
|
boolean ShowMainMenu;
|
|
|
|
|
|
|
|
|
2010-10-18 15:24:46 -03:00
|
|
|
// CLI Functions
|
|
|
|
// This can be moved later to CLI.pde
|
|
|
|
void RunCLI () {
|
|
|
|
|
2010-11-28 06:56:27 -04:00
|
|
|
// APM_RC.Init(); // APM Radio initialization
|
|
|
|
|
2010-10-30 05:30:46 -03:00
|
|
|
readUserConfig(); // Read memory values from EEPROM
|
2010-11-28 06:56:27 -04:00
|
|
|
|
2010-10-19 12:22:58 -03:00
|
|
|
ShowMainMenu = TRUE;
|
2010-10-18 15:24:46 -03:00
|
|
|
// We need to initialize Serial again due it was not initialized during startup.
|
|
|
|
SerBeg(SerBau);
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPrln();
|
|
|
|
SerPrln("Welcome to ArduCopter CLI");
|
2010-10-18 15:24:46 -03:00
|
|
|
SerPri("Firmware: ");
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPrln(VER);
|
|
|
|
SerPrln();
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPrln("Make sure that you have Carriage Return active");
|
2010-10-19 12:22:58 -03:00
|
|
|
|
|
|
|
if(ShowMainMenu) Show_MainMenu();
|
|
|
|
|
2010-10-18 15:24:46 -03:00
|
|
|
// Our main loop that never ends. Only way to get away from here is to reboot APM
|
|
|
|
for (;;) {
|
2010-12-08 07:59:14 -04:00
|
|
|
|
|
|
|
if(ShowMainMenu) Show_MainMenu();
|
|
|
|
|
|
|
|
delay(50);
|
2010-10-19 12:22:58 -03:00
|
|
|
if (SerAva()) {
|
|
|
|
ShowMainMenu = TRUE;
|
|
|
|
queryType = SerRea();
|
|
|
|
switch (queryType) {
|
2010-12-15 09:51:53 -04:00
|
|
|
case 'a':
|
|
|
|
Flip_MAG();
|
|
|
|
break;
|
2010-10-19 12:22:58 -03:00
|
|
|
case 'c':
|
|
|
|
CALIB_CompassOffset();
|
|
|
|
break;
|
2010-12-12 07:53:38 -04:00
|
|
|
case 'd':
|
|
|
|
Log_Read(1,4000);
|
|
|
|
break;
|
2010-10-30 05:30:46 -03:00
|
|
|
case 'i':
|
|
|
|
CALIB_AccOffset();
|
2010-12-08 07:59:14 -04:00
|
|
|
break;
|
|
|
|
case 't':
|
|
|
|
CALIB_Throttle();
|
|
|
|
break;
|
|
|
|
case 'e':
|
|
|
|
CALIB_Esc();
|
2010-10-30 05:30:46 -03:00
|
|
|
break;
|
2010-12-22 09:38:54 -04:00
|
|
|
case 'o':
|
|
|
|
Set_Obstacle_Avoidance_PIDs();
|
|
|
|
break;
|
2010-12-08 07:59:14 -04:00
|
|
|
case 's':
|
|
|
|
Show_Settings();
|
|
|
|
break;
|
2010-12-15 09:51:53 -04:00
|
|
|
case 'r':
|
|
|
|
Reset_Settings();
|
|
|
|
break;
|
2010-12-10 01:22:52 -04:00
|
|
|
case 'm':
|
|
|
|
RUN_Motors();
|
|
|
|
break;
|
2010-12-12 07:53:38 -04:00
|
|
|
case 'z':
|
|
|
|
Log_Erase();
|
|
|
|
break;
|
2010-10-19 12:22:58 -03:00
|
|
|
}
|
2010-12-08 07:59:14 -04:00
|
|
|
SerFlu();
|
2010-10-19 12:22:58 -03:00
|
|
|
}
|
2010-12-08 07:59:14 -04:00
|
|
|
|
2010-11-28 06:56:27 -04:00
|
|
|
// Changing LED statuses to inform that we are in CLI mode
|
|
|
|
// Blinking Red, Yellow, Green when in CLI mode
|
|
|
|
if(millis() - cli_timer > 1000) {
|
|
|
|
cli_timer = millis();
|
2010-11-28 07:16:38 -04:00
|
|
|
CLILedStep();
|
2010-11-28 06:56:27 -04:00
|
|
|
}
|
2010-12-08 07:59:14 -04:00
|
|
|
} // Mainloop ends
|
|
|
|
}
|
2010-11-28 06:56:27 -04:00
|
|
|
|
|
|
|
|
2010-10-18 15:24:46 -03:00
|
|
|
|
|
|
|
|
2010-10-19 12:22:58 -03:00
|
|
|
void Show_MainMenu() {
|
|
|
|
ShowMainMenu = FALSE;
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln();
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPrln("CLI Menu - Type your command on command prompt");
|
|
|
|
SerPrln("----------------------------------------------");
|
2010-12-15 09:51:53 -04:00
|
|
|
SerPrln(" a - Activate/Deactivate compass (check #IsMag define too)");
|
2010-12-10 01:22:52 -04:00
|
|
|
SerPrln(" c - Show/Save compass offsets");
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln(" d - dump logs to serial");
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPrln(" e - ESC Throttle calibration (Works with official ArduCopter ESCs)");
|
|
|
|
SerPrln(" i - Initialize and calibrate Accel offsets");
|
2010-12-10 01:22:52 -04:00
|
|
|
SerPrln(" m - Motor tester with AIL/ELE stick");
|
2010-12-22 09:38:54 -04:00
|
|
|
SerPrln(" o - Show/Save obstacle avoidance PIDs");
|
2010-12-15 09:51:53 -04:00
|
|
|
SerPrln(" r - Reset to factory settings");
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln(" t - Calibrate MIN Throttle value");
|
|
|
|
SerPrln(" s - Show settings");
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln(" z - clear all logs");
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPrln(" ");
|
2010-12-08 07:59:14 -04:00
|
|
|
SerFlu();
|
2010-10-19 12:22:58 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/* ************************************************************** */
|
|
|
|
// Compass/Magnetometer Offset Calibration
|
|
|
|
void CALIB_CompassOffset() {
|
|
|
|
|
|
|
|
#ifdef IsMAG
|
|
|
|
SerPrln("Rotate/Pitch/Roll your ArduCopter untill offset variables are not");
|
|
|
|
SerPrln("anymore changing, write down your offset values and update them ");
|
|
|
|
SerPrln("to their correct location. Starting in..");
|
|
|
|
SerPrln("2 secs.");
|
|
|
|
delay(1000);
|
|
|
|
SerPrln("1 secs.");
|
|
|
|
delay(1000);
|
|
|
|
SerPrln("starting now....");
|
|
|
|
|
2010-12-12 10:05:31 -04:00
|
|
|
AP_Compass.init(); // Initialization
|
|
|
|
AP_Compass.set_orientation(MAGORIENTATION); // set compass's orientation on aircraft
|
|
|
|
AP_Compass.set_offsets(0,0,0); // set offsets to account for surrounding interference
|
|
|
|
AP_Compass.set_declination(ToRad(DECLINATION)); // set local difference between magnetic north and true north
|
2010-10-19 12:22:58 -03:00
|
|
|
int counter = 0;
|
|
|
|
|
2010-12-08 08:19:21 -04:00
|
|
|
SerFlu();
|
2010-12-08 07:59:14 -04:00
|
|
|
while(1) {
|
2010-10-19 12:22:58 -03:00
|
|
|
static float min[3], max[3], offset[3];
|
|
|
|
if((millis()- timer) > 100) {
|
|
|
|
timer = millis();
|
2010-12-12 10:05:31 -04:00
|
|
|
AP_Compass.read();
|
|
|
|
AP_Compass.calculate(0,0); // roll = 0, pitch = 0 for this example
|
2010-10-19 12:22:58 -03:00
|
|
|
|
|
|
|
// capture min
|
2010-12-12 10:05:31 -04:00
|
|
|
if( AP_Compass.mag_x < min[0] ) min[0] = AP_Compass.mag_x;
|
|
|
|
if( AP_Compass.mag_y < min[1] ) min[1] = AP_Compass.mag_y;
|
|
|
|
if( AP_Compass.mag_z < min[2] ) min[2] = AP_Compass.mag_z;
|
2010-10-19 12:22:58 -03:00
|
|
|
|
|
|
|
// capture max
|
2010-12-12 10:05:31 -04:00
|
|
|
if( AP_Compass.mag_x > max[0] ) max[0] = AP_Compass.mag_x;
|
|
|
|
if( AP_Compass.mag_y > max[1] ) max[1] = AP_Compass.mag_y;
|
|
|
|
if( AP_Compass.mag_z > max[2] ) max[2] = AP_Compass.mag_z;
|
2010-10-19 12:22:58 -03:00
|
|
|
|
|
|
|
// calculate offsets
|
|
|
|
offset[0] = -(max[0]+min[0])/2;
|
|
|
|
offset[1] = -(max[1]+min[1])/2;
|
|
|
|
offset[2] = -(max[2]+min[2])/2;
|
|
|
|
|
|
|
|
// display all to user
|
|
|
|
SerPri("Heading:");
|
2010-12-12 10:05:31 -04:00
|
|
|
SerPri(ToDeg(AP_Compass.heading));
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPri(" \t(");
|
2010-12-12 10:05:31 -04:00
|
|
|
SerPri(AP_Compass.mag_x);
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPri(",");
|
2010-12-12 10:05:31 -04:00
|
|
|
SerPri(AP_Compass.mag_y);
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPri(",");
|
2010-12-12 10:05:31 -04:00
|
|
|
SerPri(AP_Compass.mag_z);
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPri(")");
|
|
|
|
|
|
|
|
// display offsets
|
|
|
|
SerPri("\t offsets(");
|
|
|
|
SerPri(offset[0]);
|
|
|
|
SerPri(",");
|
|
|
|
SerPri(offset[1]);
|
|
|
|
SerPri(",");
|
|
|
|
SerPri(offset[2]);
|
|
|
|
SerPri(")");
|
|
|
|
SerPrln();
|
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
if(counter == 200) {
|
2010-10-19 12:22:58 -03:00
|
|
|
counter = 0;
|
|
|
|
SerPrln();
|
|
|
|
SerPrln("Roll and Rotate your quad untill offsets are not changing!");
|
2010-12-08 07:59:14 -04:00
|
|
|
// SerPrln("to exit from this loop, reboot your APM");
|
2010-10-19 12:22:58 -03:00
|
|
|
SerPrln();
|
|
|
|
delay(500);
|
|
|
|
}
|
|
|
|
counter++;
|
|
|
|
}
|
2010-12-08 07:59:14 -04:00
|
|
|
if(SerAva() > 0){
|
|
|
|
|
|
|
|
mag_offset_x = offset[0];
|
|
|
|
mag_offset_y = offset[1];
|
|
|
|
mag_offset_z = offset[2];
|
|
|
|
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln("Saving Offsets to EEPROM");
|
2010-12-08 07:59:14 -04:00
|
|
|
writeEEPROM(mag_offset_x, mag_offset_x_ADR);
|
|
|
|
writeEEPROM(mag_offset_y, mag_offset_y_ADR);
|
|
|
|
writeEEPROM(mag_offset_z, mag_offset_z_ADR);
|
2010-12-08 08:19:21 -04:00
|
|
|
delay(500);
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln("Saved...");
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2010-10-19 12:22:58 -03:00
|
|
|
}
|
|
|
|
#else
|
|
|
|
SerPrln("Magneto module is not activated on Arducopter.pde");
|
|
|
|
SerPrln("Check your program #definitions, upload firmware and try again!!");
|
|
|
|
// SerPrln("Now reboot your APM");
|
|
|
|
// for(;;)
|
|
|
|
// delay(10);
|
|
|
|
#endif
|
2010-10-18 15:24:46 -03:00
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-10-30 05:30:46 -03:00
|
|
|
/* ************************************************************** */
|
|
|
|
// Accell calibration
|
|
|
|
void CALIB_AccOffset() {
|
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
int loopy;
|
|
|
|
long xx = 0, xy = 0, xz = 0;
|
2010-10-30 05:30:46 -03:00
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln("Initializing Accelerometers..");
|
2010-11-27 00:56:31 -04:00
|
|
|
adc.Init(); // APM ADC library initialization
|
2010-11-28 06:56:27 -04:00
|
|
|
// delay(250); // Giving small moment before starting
|
2010-10-30 05:30:46 -03:00
|
|
|
|
|
|
|
calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde)
|
|
|
|
|
|
|
|
SerPrln();
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln("Sampling 50 samples from Accelerometers, don't move your ArduCopter!");
|
2010-10-30 05:30:46 -03:00
|
|
|
SerPrln("Sample:\tAcc-X\tAxx-Y\tAcc-Z");
|
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
for(loopy = 1; loopy <= 50; loopy++) {
|
2010-10-30 05:30:46 -03:00
|
|
|
SerPri(" ");
|
|
|
|
SerPri(loopy);
|
|
|
|
SerPri(":");
|
|
|
|
tab();
|
2010-11-27 00:56:31 -04:00
|
|
|
SerPri(xx += adc.Ch(4));
|
2010-10-30 05:30:46 -03:00
|
|
|
tab();
|
2010-11-27 00:56:31 -04:00
|
|
|
SerPri(xy += adc.Ch(5));
|
2010-10-30 05:30:46 -03:00
|
|
|
tab();
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln(xz += adc.Ch(6));
|
|
|
|
delay(20);
|
2010-10-30 05:30:46 -03:00
|
|
|
}
|
2010-11-28 06:56:27 -04:00
|
|
|
|
2010-10-30 05:30:46 -03:00
|
|
|
xx = xx / (loopy - 1);
|
|
|
|
xy = xy / (loopy - 1);
|
2010-11-28 13:20:16 -04:00
|
|
|
xz = xz / (loopy - 1);
|
2010-12-08 07:59:14 -04:00
|
|
|
xz = xz - 407; // Z-Axis correction
|
|
|
|
// xx += 42;
|
|
|
|
|
|
|
|
acc_offset_y = xy;
|
|
|
|
acc_offset_x = xx;
|
|
|
|
acc_offset_z = xz;
|
|
|
|
|
|
|
|
AN_OFFSET[3] = acc_offset_x;
|
|
|
|
AN_OFFSET[4] = acc_offset_y;
|
|
|
|
AN_OFFSET[5] = acc_offset_z;
|
|
|
|
|
|
|
|
SerPrln();
|
|
|
|
SerPrln("Offsets as follows: ");
|
2010-10-30 05:30:46 -03:00
|
|
|
SerPri(" ");
|
|
|
|
tab();
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPri(acc_offset_x);
|
2010-10-30 05:30:46 -03:00
|
|
|
tab();
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPri(acc_offset_y);
|
2010-10-30 05:30:46 -03:00
|
|
|
tab();
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln(acc_offset_z);
|
|
|
|
|
|
|
|
SerPrln("Final results as follows: ");
|
|
|
|
SerPri(" ");
|
|
|
|
tab();
|
|
|
|
SerPri(adc.Ch(4) - acc_offset_x);
|
|
|
|
tab();
|
|
|
|
SerPri(adc.Ch(5) - acc_offset_y);
|
|
|
|
tab();
|
|
|
|
SerPrln(adc.Ch(6) - acc_offset_z);
|
|
|
|
SerPrln();
|
|
|
|
SerPrln("Final results should be close to 0, 0, 408 if they are far (-+10) from ");
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPrln("those values, redo initialization or use Configurator for finetuning");
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln();
|
|
|
|
SerPrln("Saving values to EEPROM");
|
|
|
|
writeEEPROM(acc_offset_x, acc_offset_x_ADR);
|
|
|
|
writeEEPROM(acc_offset_y, acc_offset_y_ADR);
|
|
|
|
writeEEPROM(acc_offset_z, acc_offset_z_ADR);
|
|
|
|
delay(200);
|
|
|
|
SerPrln("Saved..");
|
|
|
|
SerPrln();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-12-15 09:51:53 -04:00
|
|
|
void Flip_MAG() {
|
|
|
|
SerPrln("Activate/Deactivate Magentometer!");
|
|
|
|
SerPri("Magnetometer is now: ");
|
|
|
|
delay(500);
|
|
|
|
if(MAGNETOMETER == 0) {
|
|
|
|
MAGNETOMETER = 1;
|
|
|
|
writeEEPROM(MAGNETOMETER, MAGNETOMETER_ADR);
|
|
|
|
SerPrln("Activated");
|
|
|
|
} else {
|
|
|
|
MAGNETOMETER = 0;
|
|
|
|
writeEEPROM(MAGNETOMETER, MAGNETOMETER_ADR);
|
|
|
|
SerPrln("Deactivated");
|
|
|
|
}
|
|
|
|
delay(1000);
|
|
|
|
SerPrln("State... saved");
|
|
|
|
|
|
|
|
}
|
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
|
|
|
|
void CALIB_Throttle() {
|
2010-12-15 09:51:53 -04:00
|
|
|
int tmpThrottle = 1200;
|
2010-12-08 07:59:14 -04:00
|
|
|
|
|
|
|
SerPrln("Move your throttle to MIN, reading starts in 3 seconds");
|
|
|
|
delay(1000);
|
|
|
|
SerPrln("2. ");
|
|
|
|
delay(1000);
|
|
|
|
SerPrln("1. ");
|
|
|
|
delay(1000);
|
|
|
|
SerPrln("Reading Throttle value, hit enter to exit");
|
|
|
|
|
|
|
|
SerFlu();
|
|
|
|
while(1) {
|
|
|
|
ch_throttle = APM_RC.InputCh(CH_THROTTLE);
|
|
|
|
SerPri("Throttle channel: ");
|
|
|
|
SerPrln(ch_throttle);
|
|
|
|
if(tmpThrottle > ch_throttle) tmpThrottle = ch_throttle;
|
|
|
|
delay(50);
|
|
|
|
if(SerAva() > 0){
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln();
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPri("Lowest throttle value: ");
|
|
|
|
SerPrln(tmpThrottle);
|
|
|
|
SerPrln();
|
|
|
|
SerPrln("Saving MIN_THROTTLE to EEPROM");
|
|
|
|
writeEEPROM(tmpThrottle, MIN_THROTTLE_ADR);
|
|
|
|
delay(200);
|
|
|
|
SerPrln("Saved..");
|
|
|
|
SerPrln();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
void CALIB_Esc() {
|
|
|
|
|
|
|
|
SerPrln("Disconnect your battery if you have it connected, keep your USB cable/Xbee connected!");
|
|
|
|
SerPrln("After battery is disconnected hit enter key and wait more instructions:");
|
|
|
|
SerPrln("As safety measure, unmount all your propellers before continuing!!");
|
|
|
|
|
|
|
|
WaitSerialEnter();
|
|
|
|
|
|
|
|
SerPrln("Move your Throttle to maximum and connect your battery. ");
|
|
|
|
SerPrln("after you hear beep beep tone, move your throttle to minimum and");
|
|
|
|
SerPrln("hit enter after you are ready to disarm motors.");
|
|
|
|
SerPrln("Arming now all motors");
|
|
|
|
delay(500);
|
|
|
|
SerPrln("Motors: ARMED");
|
|
|
|
delay(200);
|
|
|
|
SerPrln("Connect your battery and let ESCs to reboot!");
|
|
|
|
while(1) {
|
|
|
|
ch_throttle = APM_RC.InputCh(CH_THROTTLE);
|
|
|
|
APM_RC.OutputCh(0, ch_throttle);
|
|
|
|
APM_RC.OutputCh(1, ch_throttle);
|
|
|
|
APM_RC.OutputCh(2, ch_throttle);
|
|
|
|
APM_RC.OutputCh(3, ch_throttle);
|
|
|
|
|
|
|
|
// InstantPWM => Force inmediate output on PWM signals
|
|
|
|
APM_RC.Force_Out0_Out1();
|
|
|
|
APM_RC.Force_Out2_Out3();
|
|
|
|
delay(20);
|
|
|
|
if(SerAva() > 0){
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
APM_RC.OutputCh(0, 900);
|
|
|
|
APM_RC.OutputCh(1, 900);
|
|
|
|
APM_RC.OutputCh(2, 900);
|
2010-12-15 09:51:53 -04:00
|
|
|
APM_RC.OutputCh(3, 900);
|
2010-12-08 07:59:14 -04:00
|
|
|
APM_RC.Force_Out0_Out1();
|
|
|
|
APM_RC.Force_Out2_Out3();
|
2010-10-19 12:22:58 -03:00
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
SerPrln("Motors: DISARMED");
|
|
|
|
SerPrln();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-12-10 01:22:52 -04:00
|
|
|
void RUN_Motors() {
|
|
|
|
|
|
|
|
long run_timer;
|
|
|
|
byte motor;
|
|
|
|
|
|
|
|
SerPrln("Move your ROLL/PITCH Stick to up/down, left/right to start");
|
|
|
|
SerPrln("corresponding motor. Motor will pulse slowly! (20% Throttle)");
|
|
|
|
SerPrln("SAFETY!! Remove all propellers before doing stick movements");
|
|
|
|
SerPrln();
|
|
|
|
SerPrln("Exit from test by hiting Enter");
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
SerFlu();
|
|
|
|
while(1) {
|
|
|
|
|
|
|
|
ch_roll = APM_RC.InputCh(CH_ROLL);
|
|
|
|
ch_pitch = APM_RC.InputCh(CH_PITCH);
|
|
|
|
|
|
|
|
if(ch_roll < 1400) {
|
2010-12-15 09:51:53 -04:00
|
|
|
SerPrln("Left Motor");
|
|
|
|
OutMotor(1);
|
|
|
|
delay(500);
|
2010-12-10 01:22:52 -04:00
|
|
|
}
|
|
|
|
if(ch_roll > 1600) {
|
2010-12-15 09:51:53 -04:00
|
|
|
SerPrln("Right Motor");
|
|
|
|
OutMotor(0);
|
|
|
|
delay(500);
|
2010-12-10 01:22:52 -04:00
|
|
|
|
|
|
|
}
|
|
|
|
if(ch_pitch < 1400) {
|
2010-12-15 09:51:53 -04:00
|
|
|
SerPrln("Front Motor");
|
|
|
|
OutMotor(2);
|
|
|
|
delay(500);
|
2010-12-10 01:22:52 -04:00
|
|
|
|
|
|
|
}
|
|
|
|
if(ch_pitch > 1600) {
|
2010-12-15 09:51:53 -04:00
|
|
|
SerPrln("Rear Motor");
|
|
|
|
OutMotor(3);
|
|
|
|
delay(500);
|
2010-12-10 01:22:52 -04:00
|
|
|
|
|
|
|
}
|
|
|
|
|
2010-12-15 09:51:53 -04:00
|
|
|
// Shuting down all motors
|
|
|
|
APM_RC.OutputCh(0, 900);
|
|
|
|
APM_RC.OutputCh(1, 900);
|
|
|
|
APM_RC.OutputCh(2, 900);
|
|
|
|
APM_RC.OutputCh(3, 900);
|
|
|
|
APM_RC.Force_Out0_Out1();
|
|
|
|
APM_RC.Force_Out2_Out3();
|
|
|
|
|
2010-12-10 01:22:52 -04:00
|
|
|
delay(100);
|
2010-12-15 09:51:53 -04:00
|
|
|
// delay(20);
|
2010-12-10 01:22:52 -04:00
|
|
|
if(SerAva() > 0){
|
|
|
|
SerFlu();
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln("Exiting motor/esc tester...");
|
2010-12-10 01:22:52 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
// Just a small ESC/Motor commander
|
|
|
|
void OutMotor(byte motor_id) {
|
|
|
|
APM_RC.OutputCh(motor_id, 1200);
|
|
|
|
APM_RC.Force_Out0_Out1();
|
|
|
|
APM_RC.Force_Out2_Out3();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-12-15 09:51:53 -04:00
|
|
|
byte Reset_Settings() {
|
|
|
|
int c;
|
|
|
|
|
|
|
|
SerPrln("Reseting EEPROM to default!");
|
|
|
|
delay(500);
|
|
|
|
SerFlu();
|
|
|
|
delay(500);
|
|
|
|
SerPrln("Hit 'Y' to reset factory settings, any other and you will return to main menu!");
|
|
|
|
do {
|
|
|
|
c = SerRea();
|
|
|
|
}
|
|
|
|
while (-1 == c);
|
|
|
|
|
|
|
|
if (('y' != c) && ('Y' != c)) {
|
|
|
|
SerPrln("EEPROM has not reseted!");
|
|
|
|
SerPrln("Returning to main menu.");
|
|
|
|
return(-1);
|
|
|
|
}
|
|
|
|
|
|
|
|
SerPrln("Reseting to factory settings!");
|
|
|
|
defaultUserConfig();
|
|
|
|
delay(200);
|
|
|
|
SerPrln("Saving to EEPROM");
|
|
|
|
writeUserConfig();
|
|
|
|
SerPrln("Done..");
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
void Show_Settings() {
|
|
|
|
// Reading current EEPROM values
|
2010-12-10 01:22:52 -04:00
|
|
|
|
|
|
|
SerPrln("ArduCopter - Current settings");
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPrln("-----------------------------");
|
|
|
|
SerPri("Firmware: ");
|
|
|
|
SerPri(VER);
|
|
|
|
SerPrln();
|
|
|
|
SerPrln();
|
2010-12-10 01:22:52 -04:00
|
|
|
|
2010-12-08 07:59:14 -04:00
|
|
|
readUserConfig();
|
|
|
|
delay(50);
|
|
|
|
|
|
|
|
SerPri("Magnetom. offsets (x,y,z): ");
|
|
|
|
SerPri(mag_offset_x);
|
|
|
|
cspc();
|
|
|
|
SerPri(mag_offset_y);
|
|
|
|
cspc();
|
|
|
|
SerPri(mag_offset_z);
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
SerPri("Accel offsets (x,y,z): ");
|
|
|
|
SerPri(acc_offset_x);
|
|
|
|
cspc();
|
|
|
|
SerPri(acc_offset_y);
|
|
|
|
cspc();
|
|
|
|
SerPri(acc_offset_z);
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
SerPri("Min Throttle: ");
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln(MIN_THROTTLE);
|
2010-12-08 07:59:14 -04:00
|
|
|
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPri("Magnetometer 1-ena/0-dis: ");
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln(MAGNETOMETER, DEC);
|
2010-12-08 08:19:21 -04:00
|
|
|
|
|
|
|
SerPri("Camera mode: ");
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln(cam_mode, DEC);
|
2010-12-10 01:22:52 -04:00
|
|
|
|
2010-12-08 08:34:02 -04:00
|
|
|
SerPri("Flight orientation: ");
|
|
|
|
if(SW_DIP1) {
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln("x mode");
|
2010-12-10 01:22:52 -04:00
|
|
|
}
|
|
|
|
else {
|
2010-12-12 07:53:38 -04:00
|
|
|
SerPrln("+ mode");
|
2010-12-08 08:34:02 -04:00
|
|
|
}
|
2010-12-22 09:38:54 -04:00
|
|
|
|
|
|
|
Show_Obstacle_Avoidance_PIDs() ;
|
2010-12-10 01:22:52 -04:00
|
|
|
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPrln();
|
2010-12-22 09:38:54 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// Display obstacle avoidance pids
|
|
|
|
void Show_Obstacle_Avoidance_PIDs() {
|
|
|
|
SerPri("\tSafetyZone: ");
|
|
|
|
SerPrln(RF_SAFETY_ZONE);
|
|
|
|
SerPri("\tRoll PID: ");
|
|
|
|
SerPri(KP_RF_ROLL); cspc();
|
|
|
|
SerPri(KI_RF_ROLL); cspc();
|
|
|
|
SerPrln(KD_RF_ROLL);
|
|
|
|
SerPri("\tPitch PID: ");
|
|
|
|
SerPri(KP_RF_PITCH); cspc();
|
|
|
|
SerPri(KI_RF_PITCH); cspc();
|
|
|
|
SerPri(KD_RF_PITCH);
|
2010-12-08 08:19:21 -04:00
|
|
|
SerPrln();
|
2010-12-22 09:38:54 -04:00
|
|
|
SerPri("\tMaxAngle: ");
|
|
|
|
SerPri(RF_MAX_ANGLE);
|
|
|
|
SerPrln();
|
|
|
|
}
|
2010-12-08 08:19:21 -04:00
|
|
|
|
2010-12-22 09:38:54 -04:00
|
|
|
// save RF pids to eeprom
|
|
|
|
void Save_Obstacle_Avoidance_PIDs_toEEPROM() {
|
|
|
|
writeEEPROM(KP_RF_ROLL,KP_RF_ROLL_ADR);
|
|
|
|
writeEEPROM(KD_RF_ROLL,KD_RF_ROLL_ADR);
|
|
|
|
writeEEPROM(KI_RF_ROLL,KI_RF_ROLL_ADR);
|
|
|
|
writeEEPROM(KP_RF_PITCH,KP_RF_PITCH_ADR);
|
|
|
|
writeEEPROM(KD_RF_PITCH,KD_RF_PITCH_ADR);
|
|
|
|
writeEEPROM(KI_RF_PITCH,KI_RF_PITCH_ADR);
|
|
|
|
writeEEPROM(RF_MAX_ANGLE,RF_MAX_ANGLE_ADR);
|
|
|
|
writeEEPROM(RF_SAFETY_ZONE,RF_SAFETY_ZONE_ADR);
|
2010-12-08 07:59:14 -04:00
|
|
|
}
|
|
|
|
|
2010-12-22 09:38:54 -04:00
|
|
|
//
|
|
|
|
void Set_Obstacle_Avoidance_PIDs() {
|
|
|
|
float tempVal1, tempVal2, tempVal3;
|
|
|
|
int saveToEeprom = 0;
|
|
|
|
// Display current PID values
|
|
|
|
SerPrln("Obstacle Avoidance:");
|
|
|
|
Show_Obstacle_Avoidance_PIDs();
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
// SAFETY ZONE
|
|
|
|
SerFlu();
|
|
|
|
SerPri("Enter Safety Zone (in cm) or 0 to skip: ");
|
|
|
|
while( !SerAva() ); // wait until user presses a key
|
|
|
|
tempVal1 = readFloatSerial();
|
|
|
|
if( tempVal1 >= 20 && tempVal1 <= 150 ) {
|
|
|
|
RF_SAFETY_ZONE = tempVal1;
|
|
|
|
SerPri("SafetyZone: ");
|
|
|
|
SerPrln(RF_SAFETY_ZONE);
|
|
|
|
}
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
// ROLL PIDs
|
|
|
|
SerFlu();
|
|
|
|
SerPri("Enter Roll P;I;D; values or 0 to skip: ");
|
|
|
|
while( !SerAva() ); // wait until user presses a key
|
|
|
|
tempVal1 = readFloatSerial();
|
|
|
|
tempVal2 = readFloatSerial();
|
|
|
|
tempVal3 = readFloatSerial();
|
|
|
|
if( tempVal1 != 0 || tempVal2 != 0 || tempVal3 != 0 ) {
|
|
|
|
KP_RF_ROLL = tempVal1;
|
|
|
|
KI_RF_ROLL = tempVal2;
|
|
|
|
KD_RF_ROLL = tempVal3;
|
|
|
|
SerPrln();
|
|
|
|
SerPri("P:");
|
|
|
|
SerPri(KP_RF_ROLL);
|
|
|
|
SerPri("\tI:");
|
|
|
|
SerPri(KI_RF_ROLL);
|
|
|
|
SerPri("\tD:");
|
|
|
|
SerPri(KD_RF_ROLL);
|
|
|
|
saveToEeprom = 1;
|
|
|
|
}
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
// PITCH PIDs
|
|
|
|
SerFlu();
|
|
|
|
SerPri("Enter Pitch P;I;D; values or 0 to skip: ");
|
|
|
|
while( !SerAva() ); // wait until user presses a key
|
|
|
|
tempVal1 = readFloatSerial();
|
|
|
|
tempVal2 = readFloatSerial();
|
|
|
|
tempVal3 = readFloatSerial();
|
|
|
|
if( tempVal1 != 0 || tempVal2 != 0 || tempVal3 != 0 ) {
|
|
|
|
KP_RF_PITCH = tempVal1;
|
|
|
|
KI_RF_PITCH = tempVal2;
|
|
|
|
KD_RF_PITCH = tempVal3;
|
|
|
|
SerPrln();
|
|
|
|
SerPri("P:");
|
|
|
|
SerPri(KP_RF_PITCH);
|
|
|
|
SerPri("\tI:");
|
|
|
|
SerPri(KI_RF_PITCH);
|
|
|
|
SerPri("\tD:");
|
|
|
|
SerPri(KD_RF_PITCH);
|
|
|
|
saveToEeprom = 1;
|
|
|
|
}
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
// Max Angle
|
|
|
|
SerFlu();
|
|
|
|
SerPri("Enter Max Angle or 0 to skip: ");
|
|
|
|
while( !SerAva() ); // wait until user presses a key
|
|
|
|
tempVal1 = readFloatSerial();
|
|
|
|
SerPrln(tempVal1);
|
|
|
|
if( tempVal1 > 0 ) {
|
|
|
|
RF_MAX_ANGLE = tempVal1;
|
|
|
|
SerPrln();
|
|
|
|
SerPri("MaxAngle: ");
|
|
|
|
SerPri(RF_MAX_ANGLE);
|
|
|
|
saveToEeprom = 1;
|
|
|
|
}
|
|
|
|
SerPrln();
|
|
|
|
|
|
|
|
// save to eeprom
|
|
|
|
if( saveToEeprom == 1 ) {
|
|
|
|
Save_Obstacle_Avoidance_PIDs_toEEPROM();
|
|
|
|
SerPrln("Saved to EEPROM");
|
|
|
|
SerPrln();
|
|
|
|
}
|
|
|
|
}
|
2010-12-08 07:59:14 -04:00
|
|
|
|
|
|
|
void cspc() {
|
|
|
|
SerPri(", ");
|
|
|
|
}
|
|
|
|
|
|
|
|
void WaitSerialEnter() {
|
|
|
|
// Flush serials
|
|
|
|
SerFlu();
|
|
|
|
delay(50);
|
|
|
|
while(1) {
|
|
|
|
if(SerAva() > 0){
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
delay(20);
|
|
|
|
}
|
|
|
|
delay(250);
|
|
|
|
SerFlu();
|
2010-10-30 05:30:46 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2010-11-28 06:56:27 -04:00
|
|
|
|
|
|
|
|
2010-12-15 09:51:53 -04:00
|
|
|
|
|
|
|
|
2010-12-22 09:38:54 -04:00
|
|
|
|