From ca21fc01eeb91b23f5842a936e87301409ecf8cb Mon Sep 17 00:00:00 2001 From: CaranchoEngineering Date: Wed, 21 Jul 2010 08:03:26 +0000 Subject: [PATCH] changed transmitter pitch direction back to how Jose had it git-svn-id: https://arducopter.googlecode.com/svn/trunk@49 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- Arducopter/Arducopter.pde | 24 ++++++++++++++++++++---- Arducopter/DCM.pde | 4 ++-- 2 files changed, 22 insertions(+), 6 deletions(-) diff --git a/Arducopter/Arducopter.pde b/Arducopter/Arducopter.pde index bbb88404fb..c00148c70f 100644 --- a/Arducopter/Arducopter.pde +++ b/Arducopter/Arducopter.pde @@ -22,6 +22,21 @@ /* GPS_UBLOX or GPS_NMEA: GPS library [optional] */ /* ********************************************************************** */ +/* +**** Switch Functions ***** +AUX1 ON = Stable Mode +AUX1 OFF = Acro Mode +GEAR ON = GPS Hold +GEAR OFF = Flight Assist (Stable Mode) + +**** LED Feedback **** +Green LED On = APM Initialization Finished +Yellow LED On = GPS Hold Mode +Yellow LED Off = Flight Assist Mode (No GPS) +Red LED On = GPS Fix +Red LED Off = No GPS Fix +*/ + #include #include #include @@ -29,6 +44,7 @@ #include // Put your GPS library here: #include // MTK GPS +//#include // EEPROM storage for user configurable values #include @@ -586,7 +602,7 @@ void loop(){ command_rx_roll = (ch_roll-CHANN_CENTER)/12.0; command_rx_roll_diff = command_rx_roll-command_rx_roll_old; command_rx_pitch_old = command_rx_pitch; - command_rx_pitch = (CHANN_CENTER-ch_pitch)/12.0; + command_rx_pitch = (ch_pitch-CHANN_CENTER)/12.0; command_rx_pitch_diff = command_rx_pitch-command_rx_pitch_old; aux_float = (ch_yaw-Neutro_yaw)/180.0; command_rx_yaw += aux_float; @@ -655,9 +671,9 @@ void loop(){ //Output GPS data //Serial.print(","); - //Serial.print(GPS.Lattitude); - //Serial.print(","); - //Serial.print(GPS.Longitude); + Serial.print(GPS.Lattitude); + Serial.print(","); + Serial.print(GPS.Longitude); // Write GPS data to DataFlash log Log_Write_GPS(GPS.Time, GPS.Lattitude,GPS.Longitude,GPS.Altitude, GPS.Ground_Speed, GPS.Ground_Course, GPS.Fix, GPS.NumSats); diff --git a/Arducopter/DCM.pde b/Arducopter/DCM.pde index cd73a922b5..2553badcc0 100644 --- a/Arducopter/DCM.pde +++ b/Arducopter/DCM.pde @@ -121,7 +121,7 @@ void Matrix_update(void) //Accel_adjust();//adjusting centrifugal acceleration. // Not used for quadcopter - #if OUTPUTMODE==1 + #if OUTPUTMODE==1 // corrected mode Update_Matrix[0][0]=0; Update_Matrix[0][1]=-G_Dt*Omega_Vector[2];//-z Update_Matrix[0][2]=G_Dt*Omega_Vector[1];//y @@ -132,7 +132,7 @@ void Matrix_update(void) Update_Matrix[2][1]=G_Dt*Omega_Vector[0];//x Update_Matrix[2][2]=0; #endif - #if OUTPUTMODE==0 + #if OUTPUTMODE==0 // uncorrected data of the gyros (with drift) Update_Matrix[0][0]=0; Update_Matrix[0][1]=-G_Dt*Gyro_Vector[2];//-z Update_Matrix[0][2]=G_Dt*Gyro_Vector[1];//y