CLI info leds, mode fixes

git-svn-id: https://arducopter.googlecode.com/svn/trunk@972 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jphelirc 2010-11-28 10:56:27 +00:00
parent 85dc8a2cc4
commit 4a4fc212cf
7 changed files with 108 additions and 29 deletions

View File

@ -116,9 +116,9 @@ TODO:
#define CAM_SMOOTHING 1000 // Camera movement smoothing on pitch axis
#define CAM_SMOOTHING_ROLL -400 // Camera movement smoothing on roll axis
#define CAM_TILT_OUT 6 // OUTx pin for Tilt servo
#define CAM_ROLL_OUT 7 // OUTx pin for Roll servo
#define CAM_YAW_OUT 7 // OUTx pin for Yaw servo (often same as Roll)
#define CAM_TILT_OUT 4 // OUTx pin for Tilt servo
#define CAM_ROLL_OUT 5 // OUTx pin for Roll servo
#define CAM_YAW_OUT 5 // OUTx pin for Yaw servo (often same as Roll)
#define CAM_TILT_CH CH_7 // Channel for radio knob to controll tilt "zerolevel"

View File

@ -325,6 +325,9 @@ byte gled_status = HIGH;
long gled_timer;
int gled_speed;
long cli_timer;
byte cli_status = LOW;
long t0;
int num_iter;
float aux_debug;

View File

@ -119,18 +119,19 @@
// Magneto orientation and corrections.
// If you don't have magneto activated, It is safe to ignore these
//#ifdef IsMAG
#define MAGORIENTATION APM_COMPASS_COMPONENTS_UP_PINS_FORWARD // This is default solution for ArduCopter
//#define MAGORIENTATION APM_COMPASS_COMPONENTS_UP_PINS_FORWARD // This is default solution for ArduCopter
//#define MAGORIENTATION APM_COMPASS_COMPONENTS_UP_PINS_BACK // Alternative orientation for ArduCopter
//#define MAGORIENTATION APM_COMPASS_COMPONENTS_DOWN_PINS_FORWARD // If you have soldered Magneto to IMU shield in WIki pictures shows
#define MAGORIENTATION APM_COMPASS_COMPONENTS_DOWN_PINS_FORWARD // If you have soldered Magneto to IMU shield in WIki pictures shows
// To get Magneto offsets, switch to CLI mode and run offset calibration. During calibration
// you need to roll/bank/tilt/yaw/shake etc your ArduCopter. Don't kick like Jani always does :)
#define MAGOFFSET 0,0,0
//#define MAGOFFSET 0,0,0
#define MAGOFFSET 19.00,-72.00,-79.50
// Declination is a correction factor between North Pole and real magnetic North. This is different on every location
// IF you want to use really accurate headholding and future navigation features, you should update this
// You can check Declination to your location from http://www.magnetic-declination.com/
#define DECLINATION 0.0
#define DECLINATION 0.61
// And remember result from NOAA website is in form of DEGREES°MINUTES'. Degrees you can use directly but Minutes you need to
// recalculate due they one degree is 60 minutes.. For example Jani's real declination is 0.61, correct way to calculate this is
@ -222,6 +223,19 @@ void setup() {
Read_adc_raw(); // Initialize ADC readings...
#ifdef SerXbee
Serial.begin(SerBau);
Serial.print("ArduCopter v");
Serial.println(VER);
Serial.println("Serial data on Telemetry port");
Serial.println("No commands or output on this serial, check your Arducopter.pde if needed to change.");
Serial.println();
Serial.println("General info:");
if(!SW_DIP1) Serial.println("Flight mode: + ");
if(SW_DIP1) Serial.println("Flight mode: x ");
#endif
delay(10);
digitalWrite(LED_Green,HIGH); // Ready to go...
}

View File

@ -39,7 +39,7 @@ boolean ShowMainMenu;
// This can be moved later to CLI.pde
void RunCLI () {
// APM_RC.Init(); // APM Radio initialization
// APM_RC.Init(); // APM Radio initialization
readUserConfig(); // Read memory values from EEPROM
@ -69,6 +69,22 @@ void RunCLI () {
break;
}
}
// 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();
if(cli_status == HIGH) {
LEDAllOFF();
cli_status = LOW;
}
else {
LEDAllON();
cli_status = HIGH;
}
}
} // Mainloop ends
}
@ -78,7 +94,7 @@ void Show_MainMenu() {
SerPrln("CLI Menu - Type your command on command prompt");
SerPrln("----------------------------------------------");
SerPrln(" c - Show compass offsets (no return, reboot)");
SerPrln(" i - Initialize and calibrate Accel offsets");
SerPrln(" i - Initialize and calibrate Accel offsets (under work)");
SerPrln(" ");
}
@ -176,7 +192,7 @@ void CALIB_AccOffset() {
uint16_t xx = 0, xy = 0, xz = 0;
adc.Init(); // APM ADC library initialization
// delay(250); // Giving small moment before starting
// delay(250); // Giving small moment before starting
calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde)
@ -189,12 +205,12 @@ void CALIB_AccOffset() {
SerPri(loopy);
SerPri(":");
tab();
/* SerPri(xx += read_adc(4));
tab();
SerPri(xy += -read_adc(3));
tab();
SerPrln(xz += read_adc(5));
*/
/* SerPri(xx += read_adc(4));
tab();
SerPri(xy += -read_adc(3));
tab();
SerPrln(xz += read_adc(5));
*/
SerPri(xx += adc.Ch(4));
tab();
SerPri(xy += adc.Ch(5));
@ -224,3 +240,5 @@ void CALIB_AccOffset() {
}

View File

@ -139,6 +139,25 @@ int limitRange(int data, int minLimit, int maxLimit) {
}
void CLILeds (byte ledstep) {
}
void LEDAllON() {
digitalWrite(LED_Green, HIGH);
digitalWrite(LED_Red, HIGH);
digitalWrite(LED_Yellow, HIGH);
}
void LEDAllOFF() {
digitalWrite(LED_Green, LOW);
digitalWrite(LED_Red, LOW);
digitalWrite(LED_Yellow, LOW);
}
//
// Camera functions moved to event due it's and event 31-10-10, jp

View File

@ -364,7 +364,8 @@ void sendSerialTelemetry() {
SerPri(read_adc(3));
comma();
SerPri(read_adc(5));
/* comma();
comma();
SerPri(APM_Compass.Heading, 4);
comma();
SerPri(APM_Compass.Heading_X, 4);
@ -377,7 +378,7 @@ void sendSerialTelemetry() {
comma();
SerPri(APM_Compass.Mag_Z);
comma();
*/
SerPriln();
break;
case 'T': // Spare
@ -458,6 +459,30 @@ void sendSerialTelemetry() {
tab();
SerPriln();
break;
#ifdef IsGPS
case '4': // Jani's debugs
// Log_Write_GPS(GPS.Time, GPS.Lattitude, GPS.Longitude, GPS.Altitude, GPS.Altitude, GPS.Ground_Speed, GPS.Ground_Course, GPS.Fix, GPS.NumSats);
SerPri(GPS.Time);
tab();
SerPri(GPS.Lattitude);
tab();
SerPri(GPS.Longitude);
tab();
SerPri(GPS.Altitude);
tab();
SerPri(GPS.Ground_Speed);
tab();
SerPri(GPS.Ground_Course);
tab();
SerPri(GPS.Fix);
tab();
SerPri(GPS.NumSats);
tab();
SerPriln();
break;
#endif
case '.': // Modify GPS settings, print directly to GPS Port
Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n");
break;

View File

@ -76,7 +76,7 @@ void read_radio()
ch_throttle = channel_filter(tempThrottle, ch_throttle);
// Flight mode
if(ch_aux2 > 1200)
if(ch_aux2 > 1300)
flightMode = ACRO_MODE; // Force to Acro mode from radio
else
flightMode = STABLE_MODE; // Stable mode (default)
@ -84,7 +84,7 @@ void read_radio()
// Autopilot mode (only works on Stable mode)
if (flightMode == STABLE_MODE)
{
if(ch_aux < 1200)
if(ch_aux < 1300)
AP_mode = AP_AUTOMATIC_MODE; // Automatic mode : GPS position hold mode + altitude hold
else
AP_mode = AP_NORMAL_MODE; // Normal mode