mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
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
This commit is contained in:
parent
00dde93d5a
commit
ca21fc01ee
@ -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 <Wire.h>
|
||||
#include <APM_ADC.h>
|
||||
#include <APM_RC.h>
|
||||
@ -29,6 +44,7 @@
|
||||
#include <APM_Compass.h>
|
||||
// Put your GPS library here:
|
||||
#include <GPS_NMEA.h> // MTK GPS
|
||||
//#include <GPS_UBLOX.h>
|
||||
|
||||
// EEPROM storage for user configurable values
|
||||
#include <EEPROM.h>
|
||||
@ -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);
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user