cleanup: removed archive directory
this will still be in git history, but isn't needed in the tree
This commit is contained in:
parent
8f5da03f93
commit
2dd757a20f
@ -1,152 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : UserDefines.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
/*************************************************************/
|
||||
// Airframe
|
||||
#define QUAD 0
|
||||
#define HELI 1
|
||||
|
||||
// Note: do not change AIRFRAME to HELI and then load it into a QUAD or you will end up with your engines going to 50% during the initialisation sequence
|
||||
#define AIRFRAME QUAD
|
||||
|
||||
/*************************************************************/
|
||||
// Safety & Security
|
||||
|
||||
// Arm & Disarm delays
|
||||
#define ARM_DELAY 50 // how long you need to keep rudder to max right for arming motors (units*0.02, 50=1second)
|
||||
#define DISARM_DELAY 25 // how long you need to keep rudder to max left for disarming motors
|
||||
#define SAFETY_DELAY 25 // how long you need to keep throttle to min before safety activates and does not allow sudden throttle increases
|
||||
#define SAFETY_MAX_THROTTLE_INCREASE 100 // how much of jump in throttle (within a single cycle, 5ms) will cause motors to disarm
|
||||
|
||||
/*************************************************************/
|
||||
// AM Mode & Flight information
|
||||
|
||||
/* AM PIN Definitions */
|
||||
/* Will be moved in future to AN extension ports */
|
||||
/* due need to have PWM pins free for sonars and servos */
|
||||
|
||||
|
||||
#define FR_LED 3 // Mega PE4 pin, OUT7
|
||||
#define RE_LED 2 // Mega PE5 pin, OUT6
|
||||
#define RI_LED 7 // Mega PH4 pin, OUT5
|
||||
#define LE_LED 8 // Mega PH5 pin, OUT4
|
||||
|
||||
/*
|
||||
#define FR_LED AN12 // Mega PE4 pin, OUT7
|
||||
#define RE_LED AN14 // Mega PE5 pin, OUT6
|
||||
#define RI_LED AN10 // Mega PH4 pin, OUT5
|
||||
#define LE_LED AN8 // Mega PH5 pin, OUT4
|
||||
*/
|
||||
|
||||
|
||||
/*************************************************************/
|
||||
// Special patterns for future use
|
||||
|
||||
/*
|
||||
#define POFF L1\0x00\0x00\0x05
|
||||
#define PALL L1\0xFF\0xFF\0x05
|
||||
|
||||
#define GPS_AM_PAT1 L\0x00\0x00\0x05
|
||||
#define GPS_AM_PAT2 L\0xFF\0xFF\0x05
|
||||
#define GPS_AM_PAT3 L\0xF0\0xF0\0x05
|
||||
*/
|
||||
|
||||
/* AM PIN Definitions - END */
|
||||
|
||||
/*************************************************************/
|
||||
// Radio related definitions
|
||||
#define CH_ROLL 0
|
||||
#define CH_PITCH 1
|
||||
#define CH_THROTTLE 2
|
||||
#define CH_RUDDER 3
|
||||
#define CH_1 0
|
||||
#define CH_2 1
|
||||
#define CH_3 2
|
||||
#define CH_4 3
|
||||
#define CH_5 4
|
||||
#define CH_6 5
|
||||
#define CH_7 6
|
||||
#define CH_8 7
|
||||
|
||||
#define ROLL_MID 1500 // Radio Roll channel mid value
|
||||
#define PITCH_MID 1500 // Radio Pitch channel mid value
|
||||
#define YAW_MID 1500 // Radio Yaw channel mid value
|
||||
#define THROTTLE_MID 1505 // Radio Throttle channel mid value
|
||||
#define AUX_MID 1500
|
||||
|
||||
#define CHANN_CENTER 1500 // Channel center, legacy
|
||||
|
||||
// legacy, moved to EEPROM
|
||||
//#define MIN_THROTTLE 1040 // Throttle pulse width at minimun...
|
||||
|
||||
/* ******************************************************** */
|
||||
// Camera related settings
|
||||
|
||||
#define CAM_CENT 1500 // Camera center
|
||||
#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 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"
|
||||
|
||||
|
||||
|
||||
/*************************************************************/
|
||||
// General definitions
|
||||
//Modes
|
||||
#define STABLE_MODE 0
|
||||
#define ACRO_MODE 1
|
||||
#define AP_NORMAL_MODE 0 // AP disabled => manual flight
|
||||
#define AP_AUTOMATIC_MODE 1 // AP Enabled => Automatic mode (GPS position hold)
|
||||
|
||||
//Axis
|
||||
#define ROLL 0
|
||||
#define PITCH 1
|
||||
#define YAW 2
|
||||
#define XAXIS 0
|
||||
#define YAXIS 1
|
||||
#define ZAXIS 2
|
||||
|
||||
#define GYROZ 0
|
||||
#define GYROX 1
|
||||
#define GYROY 2
|
||||
#define ACCELX 3
|
||||
#define ACCELY 4
|
||||
#define ACCELZ 5
|
||||
#define LASTSENSOR 6
|
||||
|
@ -1,749 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Arducopter.h
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
#include "WProgram.h"
|
||||
|
||||
|
||||
/* ************************************************************** */
|
||||
/* APM Hardware definitions */
|
||||
|
||||
#define LED_Yellow 36 // A_LED
|
||||
#define LED_Green 37 // B_LED
|
||||
#define LED_Red 35 // C_LED
|
||||
|
||||
#define A_LED_PIN LED_Green // For legacy issues
|
||||
#define B_LED_PIN LED_Yellow
|
||||
#define C_LED_PIN LED_Red
|
||||
|
||||
// Programmable hardware switches/relays
|
||||
#define RELAY 47 // Onboard relay (PL2)
|
||||
#define SW1 41 // Push button close to I2C port (PG0)
|
||||
#define SW2 40 // Slide switch next to DIP switched (PG1)
|
||||
|
||||
// Due limitations of Arduino libraries, these pins needs to be controlled differently so no real PIN numbers
|
||||
//#define DIP1 (PE7)
|
||||
//#define DIP2 (PE6)
|
||||
//#define DIP3 (PL6)
|
||||
//#define DIP4 (PL/)
|
||||
|
||||
/* ************************************************************** */
|
||||
/* Expansion PIN's that people can use for various things. */
|
||||
|
||||
// AN0 - 7 are located at edge of IMU PCB "above" pressure sensor and Expansion port
|
||||
// AN0 - 5 are also located next to voltage dividers and sliding SW2 switch
|
||||
// AN0 - 3 has 10kOhm resistor in serial, include 3.9kOhm to make it as voltage divider
|
||||
// AN4 - 5 are direct GPIO pins from atmega1280 and they are the latest pins next to SW2 switch
|
||||
// Look more ArduCopter Wiki for voltage dividers and other ports
|
||||
#define AN0 54 // resistor, vdiv use, divider 1 closest to relay
|
||||
#define AN1 55 // resistor, vdiv use, divider 2
|
||||
#define AN2 56 // resistor, vdiv use, divider 3
|
||||
#define AN3 57 // resistor, vdiv use, divider 4 closest to SW2
|
||||
#define AN4 58 // direct GPIO pin, default as analog input, next to SW2 switch
|
||||
#define AN5 59 // direct GPIO pin, default as analog input, next to SW2 switch
|
||||
#define AN6 60 // direct GPIO pin, default as analog input, close to Pressure sensor, Expansion Ports
|
||||
#define AN7 61 // direct GPIO pin, default as analog input, close to Pressure sensor, Expansion Ports
|
||||
|
||||
// AN8 - 15 are located at edge of IMU PCB "above" pressure sensor and Expansion port
|
||||
// AN8 - 15 PINs are not connected anywhere, they are located as last 8 pins on edge of the board above Expansion Ports
|
||||
// even pins (8,10,12,14) are at edge of board, Odd pins (9,11,13,15) are on inner row
|
||||
#define AN8 62 // NC
|
||||
#define AN9 63 // NC
|
||||
#define AN10 64 // NC
|
||||
#define AN11 65 // NC
|
||||
#define AN12 66 // NC
|
||||
#define AN13 67 // NC
|
||||
#define AN14 68 // NC
|
||||
#define AN15 69 // NC
|
||||
|
||||
// Defines for Voltage Dividers
|
||||
#define VDIV1 AN0 // AN0 as default and primary
|
||||
#define VDIV2 AN1 // AN1 for secondary battery
|
||||
#define VDIV3 AN2
|
||||
#define VDIV4 AN3
|
||||
|
||||
|
||||
/* ************************************************** */
|
||||
#define EE_LAST_LOG_PAGE 0xE00
|
||||
#define EE_LAST_LOG_NUM 0xE02
|
||||
#define EE_LOG_1_START 0xE04
|
||||
|
||||
/* ************************************************** */
|
||||
/* Serial port definitions */
|
||||
#define SERIAL0_BAUD 38400 // this is the main USB out 38400 57600 115200
|
||||
#define SERIAL1_BAUD 115200
|
||||
#define SERIAL2_BAUD 115200
|
||||
#define SERIAL3_BAUD 115200
|
||||
|
||||
#ifdef SerXbee // Xbee/Telemetry port
|
||||
//#define SerBau 115200 // Baud setting moved close next to port selection
|
||||
#define SerPri Serial3.print
|
||||
#define SerPrln Serial3.println
|
||||
#define SerPriln Serial3.println
|
||||
#define SerRea Serial3.read
|
||||
#define SerAva Serial3.available
|
||||
#define SerRea Serial3.read
|
||||
#define SerFlu Serial3.flush
|
||||
#define SerBeg Serial3.begin
|
||||
#define SerP Serial3.printf_P
|
||||
#define SerPor "FTDI"
|
||||
#endif
|
||||
|
||||
#ifndef SerXbee // If we don't have SerXbee set, it means we have are using Serial0
|
||||
//#define SerBau 115200 // Baud setting moved close next to port selection
|
||||
#define SerPri Serial.print
|
||||
#define SerPrln Serial.println
|
||||
#define SerPriln Serial.println
|
||||
#define SerRea Serial.read
|
||||
#define SerAva Serial.available
|
||||
#define SerRea Serial.read
|
||||
#define SerFlu Serial.flush
|
||||
#define SerBeg Serial.begin
|
||||
#define SerP Serial.printf_P
|
||||
#define SerPor "Telemetry"
|
||||
#endif
|
||||
|
||||
|
||||
/* *********************************************** */
|
||||
// IMU definitions
|
||||
// Sensor: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ
|
||||
uint8_t sensors[6] = {1, 2, 0, 4, 5, 6}; // For ArduPilot Mega Sensor Shield Hardware
|
||||
|
||||
// Sensor: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ, MAGX, MAGY, MAGZ
|
||||
int SENSOR_SIGN[]={
|
||||
1, -1, -1, -1, 1, 1, -1, -1, -1};
|
||||
//{-1,1,-1,1,-1,1,-1,-1,-1};
|
||||
/* APM Hardware definitions, END */
|
||||
|
||||
/* *********************************************** */
|
||||
/* General definitions */
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ON 1
|
||||
#define OFF 0
|
||||
|
||||
|
||||
// ADC : Voltage reference 3.3v / 12bits(4096 steps) => 0.8mV/ADC step
|
||||
// ADXL335 Sensitivity(from datasheet) => 330mV/g, 0.8mV/ADC step => 330/0.8 = 412
|
||||
// Tested value : 408
|
||||
#define GRAVITY 408 //this equivalent to 1G in the raw data coming from the accelerometer
|
||||
#define Accel_Scale(x) x*(GRAVITY/9.81)//Scaling the raw data of the accel to actual acceleration in meters for seconds square
|
||||
|
||||
#define ROLL_DEF 0 // Level values for roll, used to calculate roll_acc_offset
|
||||
#define PITCH_DEF 0 // Level values for pitch, used to calculate pitch_acc_offset
|
||||
#define Z_DEF GRAVITY // Stable level value for Z, used to calculate z_acc_offset, same as GRAVITY
|
||||
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
// IDG500 Sensitivity (from datasheet) => 2.0mV/º/s, 0.8mV/ADC step => 0.8/3.33 = 0.4
|
||||
// Tested values :
|
||||
#define Gyro_Gain_X 0.4 //X axis Gyro gain
|
||||
#define Gyro_Gain_Y 0.4 //Y axis Gyro gain
|
||||
#define Gyro_Gain_Z 0.4 //Z axis Gyro gain
|
||||
#define Gyro_Scaled_X(x) x*ToRad(Gyro_Gain_X) //Return the scaled ADC raw data of the gyro in radians for second
|
||||
#define Gyro_Scaled_Y(x) x*ToRad(Gyro_Gain_Y) //Return the scaled ADC raw data of the gyro in radians for second
|
||||
#define Gyro_Scaled_Z(x) x*ToRad(Gyro_Gain_Z) //Return the scaled ADC raw data of the gyro in radians for second
|
||||
|
||||
/*For debugging purposes*/
|
||||
#define OUTPUTMODE 1 //If value = 1 will print the corrected data, 0 will print uncorrected data of the gyros (with drift), 2 Accel only data
|
||||
|
||||
// Altitude control methods
|
||||
#define ALTITUDE_CONTROL_NONE 0
|
||||
#define ALTITUDE_CONTROL_BARO 1
|
||||
#define ALTITUDE_CONTROL_SONAR 2
|
||||
#define SONAR_STATUS_BAD 0
|
||||
#define SONAR_STATUS_OK 1
|
||||
|
||||
int AN[6]; //array that store the 6 ADC channels
|
||||
int AN_OFFSET[6]; //Array that store the Offset of the gyros and accelerometers
|
||||
int gyro_temp;
|
||||
|
||||
|
||||
float G_Dt=0.02; // Integration time for the gyros (DCM algorithm)
|
||||
float Accel_Vector[3]= {0, 0, 0}; // Store the acceleration in a vector
|
||||
float Accel_Vector_unfiltered[3]= {0, 0, 0}; // Store the acceleration in a vector
|
||||
float Gyro_Vector[3]= {0, 0, 0}; // Store the gyros rutn rate in a vector
|
||||
float Omega_Vector[3]= {0, 0, 0}; // Corrected Gyro_Vector data
|
||||
float Omega_P[3]= {0, 0, 0}; // Omega Proportional correction
|
||||
float Omega_I[3]= {0, 0, 0}; // Omega Integrator
|
||||
float Omega[3]= {0, 0, 0};
|
||||
//float Accel_magnitude;
|
||||
//float Accel_weight;
|
||||
|
||||
float errorRollPitch[3] = {0, 0, 0};
|
||||
float errorYaw[3] = {0, 0, 0};
|
||||
float errorCourse = 0;
|
||||
float COGX = 0; // Course overground X axis
|
||||
float COGY = 1; // Course overground Y axis
|
||||
|
||||
float roll = 0;
|
||||
float pitch = 0;
|
||||
float yaw = 0;
|
||||
|
||||
unsigned int counter = 0;
|
||||
|
||||
float DCM_Matrix[3][3]= {
|
||||
{ 1,0,0 },
|
||||
{ 0,1,0 },
|
||||
{ 0,0,1 }};
|
||||
|
||||
float Update_Matrix[3][3]={
|
||||
{ 0,1,2 },
|
||||
{ 3,4,5 },
|
||||
{ 6,7,8 }}; //Gyros here
|
||||
|
||||
float Temporary_Matrix[3][3]={
|
||||
{ 0,0,0 },
|
||||
{ 0,0,0 },
|
||||
{ 0,0,0 }};
|
||||
|
||||
// GPS variables
|
||||
float speed_3d=0;
|
||||
int GPS_ground_speed=0;
|
||||
|
||||
// Main timers
|
||||
long timer=0;
|
||||
long timer_old;
|
||||
long GPS_timer;
|
||||
long GPS_timer_old;
|
||||
float GPS_Dt=0.2; // GPS Dt
|
||||
|
||||
// Attitude control variables
|
||||
float command_rx_roll=0; // User commands
|
||||
float command_rx_roll_old;
|
||||
float command_rx_roll_diff;
|
||||
float command_rx_pitch=0;
|
||||
float command_rx_pitch_old;
|
||||
float command_rx_pitch_diff;
|
||||
float command_rx_yaw=0;
|
||||
float command_rx_yaw_diff;
|
||||
int control_roll; // PID control results
|
||||
int control_pitch;
|
||||
int control_yaw;
|
||||
//float K_aux;
|
||||
|
||||
|
||||
boolean SW_DIP1; // closest to SW2 slider switch
|
||||
boolean SW_DIP2;
|
||||
boolean SW_DIP3;
|
||||
boolean SW_DIP4; // closest to header pins
|
||||
|
||||
boolean BATTLOW = FALSE; // We should be always FALSE, if we are TRUE.. it means destruction is close,
|
||||
// shut down all secondary systems that uses our precious mAh's
|
||||
|
||||
// Attitude PID controls
|
||||
float roll_I=0;
|
||||
float roll_D;
|
||||
float err_roll;
|
||||
float pitch_I=0;
|
||||
float pitch_D;
|
||||
float err_pitch;
|
||||
float yaw_I=0;
|
||||
float yaw_D;
|
||||
float err_yaw;
|
||||
float heading_I=0; // used only by heli
|
||||
|
||||
//Position control
|
||||
long target_longitude;
|
||||
long target_lattitude;
|
||||
byte target_position;
|
||||
float gps_err_roll;
|
||||
float gps_err_roll_old;
|
||||
float gps_roll_D;
|
||||
float gps_roll_I=0;
|
||||
float gps_err_pitch;
|
||||
float gps_err_pitch_old;
|
||||
float gps_pitch_D;
|
||||
float gps_pitch_I=0;
|
||||
float command_gps_roll;
|
||||
float command_gps_pitch;
|
||||
float gps_err_lat;
|
||||
float gps_err_lat_old;
|
||||
float gps_lat_D;
|
||||
float gps_lat_I=0;
|
||||
float gps_err_lon;
|
||||
float gps_err_lon_old;
|
||||
float gps_lon_D;
|
||||
float gps_lon_I=0;
|
||||
|
||||
// object avoidance
|
||||
float RF_roll_I=0;
|
||||
float RF_pitch_I=0;
|
||||
float RF_throttle_I=0;
|
||||
float command_RF_roll = 0;
|
||||
float command_RF_pitch = 0;
|
||||
float command_RF_throttle = 0;
|
||||
byte RF_new_data = 0;
|
||||
|
||||
//Altitude control variables
|
||||
int altitude_control_method = ALTITUDE_CONTROL_NONE; // switch to indicate whether we are using Sonar or Barometer
|
||||
int initial_throttle; // the base throttle value used for the control PIDs. captured when user switched into autopilot
|
||||
int err_altitude;
|
||||
int err_altitude_old;
|
||||
int ch_throttle_altitude_hold; // throttle value passed to motor_output function
|
||||
|
||||
//Barometer Sensor variables
|
||||
long target_baro_altitude; // target altitude in cm
|
||||
long press_baro_altitude = 0;
|
||||
byte baro_new_data = 0;
|
||||
float baro_altitude_I;
|
||||
float baro_altitude_D;
|
||||
|
||||
// Sonar Sensor variables
|
||||
int target_sonar_altitude; // target altitude in cm
|
||||
long press_sonar_altitude = 0;
|
||||
int sonar_status = SONAR_STATUS_BAD; // indicates if sonar values can be trusted
|
||||
int sonar_valid_count = 0; // from -5 ~ 5 -ve = number of invalid readings, +ve = number of valid readings (in a row)
|
||||
long sonar_threshold; // threshold at which we should transfer control to barometer (normally 80% of sonar's max distance)
|
||||
byte sonar_new_data = 0;
|
||||
float sonar_altitude_I;
|
||||
float sonar_altitude_D;
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
|
||||
|
||||
#define AIRSPEED_PIN 1 // Need to correct value
|
||||
#define BATTERY_PIN 1 // Need to correct value
|
||||
#define RELAY_PIN 47
|
||||
#define LOW_VOLTAGE 11.4 // Pack voltage at which to trigger alarm
|
||||
#define INPUT_VOLTAGE 5.2 // (Volts) voltage your power regulator is feeding your ArduPilot to have an accurate pressure and battery
|
||||
// level readings. (you need a multimeter to measure and set this of course)
|
||||
#define VOLT_DIV_RATIO 1.0 // Voltage divider ratio set with thru-hole resistor (see manual)
|
||||
|
||||
float battery_voltage = LOW_VOLTAGE * 1.05; // Battery Voltage, initialized above threshold for filter
|
||||
|
||||
// AP_mode : 1=> Position hold 2=>Stabilization assist mode (normal mode)
|
||||
byte AP_mode = 2;
|
||||
//byte cam_mode = 0; // moved to general settings, 31-10-10, jp
|
||||
|
||||
// Mode LED timers and variables, used to blink LED_Green
|
||||
byte gled_status = HIGH;
|
||||
long gled_timer;
|
||||
int gled_speed;
|
||||
|
||||
long cli_timer;
|
||||
byte cli_status = LOW;
|
||||
byte cli_step;
|
||||
|
||||
long t0;
|
||||
int num_iter;
|
||||
float aux_debug;
|
||||
|
||||
// Radio definitions
|
||||
int roll_mid;
|
||||
int pitch_mid;
|
||||
int yaw_mid;
|
||||
|
||||
int Neutro_yaw;
|
||||
int ch_roll;
|
||||
int ch_pitch;
|
||||
int ch_throttle;
|
||||
int ch_yaw;
|
||||
int ch_aux;
|
||||
int ch_aux2;
|
||||
|
||||
int frontMotor;
|
||||
int backMotor;
|
||||
int leftMotor;
|
||||
int rightMotor;
|
||||
byte motorArmed = 0; // 0 = motors disarmed, 1 = motors armed
|
||||
byte motorSafety = 1; // 0 = safety off, 1 = on. When On, sudden increases in throttle not allowed
|
||||
int minThrottle = 0;
|
||||
boolean flightOrientation = 0; // 0 = +, 1 = x this is read from DIP1 switch during system bootup
|
||||
|
||||
// Serial communication
|
||||
char queryType;
|
||||
long tlmTimer = 0;
|
||||
|
||||
// Arming/Disarming
|
||||
uint8_t Arming_counter=0;
|
||||
uint8_t Disarming_counter=0;
|
||||
uint8_t Safety_counter=0;
|
||||
|
||||
// Performance monitoring
|
||||
// ----------------------
|
||||
long perf_mon_timer = 0;
|
||||
float imu_health = 0; //Metric based on accel gain deweighting
|
||||
int G_Dt_max = 0; //Max main loop cycle time in milliseconds
|
||||
byte gyro_sat_count = 0;
|
||||
byte adc_constraints = 0;
|
||||
byte renorm_sqrt_count = 0;
|
||||
byte renorm_blowup_count = 0;
|
||||
int gps_fix_count = 0;
|
||||
byte gcs_messages_sent = 0;
|
||||
|
||||
// System Timers
|
||||
// --------------
|
||||
unsigned long fast_loopTimer = 0; // Time in miliseconds of main control loop
|
||||
unsigned long medium_loopTimer = 0; // Time in miliseconds of navigation control loop
|
||||
byte medium_loopCounter = 0; // Counters for branching from main control loop to slower loops
|
||||
byte slow_loopCounter = 0; //
|
||||
unsigned long deltaMiliSeconds = 0; // Delta Time in miliseconds
|
||||
unsigned long dTnav = 0; // Delta Time in milliseconds for navigation computations
|
||||
int mainLoop_count = 0;
|
||||
unsigned long elapsedTime = 0; // for doing custom events
|
||||
//unsigned int GPS_timer = 0;
|
||||
|
||||
|
||||
|
||||
/* ******************************************************** */
|
||||
/* Logging Stuff - These should be 1 (on) or 0 (off) */
|
||||
|
||||
#define LOG_ATTITUDE 1 // Logs basic attitude info
|
||||
#define LOG_GPS 1 // Logs GPS info
|
||||
#define LOG_PM 1 // Logs IMU performance monitoring info£
|
||||
#define LOG_CTUN 0 // Logs control loop tuning info
|
||||
#define LOG_NTUN 0 // Logs navigation loop tuning info
|
||||
#define LOG_MODE 1 // Logs mode changes
|
||||
#define LOG_RAW 0 // Logs raw accel/gyro data
|
||||
#define LOG_SEN 1 // Logs sensor data
|
||||
#define LOG_RANGEFINDER 0 // Logs data from range finders
|
||||
|
||||
// GCS Message ID's
|
||||
#define MSG_ACKNOWLEDGE 0x00
|
||||
#define MSG_HEARTBEAT 0x01
|
||||
#define MSG_ATTITUDE 0x02
|
||||
#define MSG_LOCATION 0x03
|
||||
#define MSG_PRESSURE 0x04
|
||||
#define MSG_STATUS_TEXT 0x05
|
||||
#define MSG_PERF_REPORT 0x06
|
||||
#define MSG_COMMAND 0x22
|
||||
#define MSG_VALUE 0x32
|
||||
#define MSG_PID 0x42
|
||||
#define MSG_TRIMS 0x50
|
||||
#define MSG_MINS 0x51
|
||||
#define MSG_MAXS 0x52
|
||||
#define MSG_IMU_OUT 0x53
|
||||
|
||||
#define SEVERITY_LOW 1
|
||||
#define SEVERITY_MEDIUM 2
|
||||
#define SEVERITY_HIGH 3
|
||||
#define SEVERITY_CRITICAL 4
|
||||
|
||||
// Debug options - set only one of these options to 1 at a time, set the others to 0
|
||||
#define DEBUG_SUBSYSTEM 0 // 0 = no debug
|
||||
// 1 = Debug the Radio input
|
||||
// 2 = Debug the Servo output
|
||||
// 3 = Debug the Sensor input
|
||||
// 4 = Debug the GPS input
|
||||
// 5 = Debug the GPS input - RAW HEX OUTPUT
|
||||
// 6 = Debug the IMU
|
||||
// 7 = Debug the Control Switch
|
||||
// 8 = Debug the Servo DIP switches
|
||||
// 9 = Debug the Relay out
|
||||
// 10 = Debug the Magnetometer
|
||||
// 11 = Debug the ABS pressure sensor
|
||||
// 12 = Debug the stored waypoints
|
||||
// 13 = Debug the Throttle
|
||||
// 14 = Debug the Radio Min Max
|
||||
// 15 = Debug the EEPROM - Hex Dump
|
||||
|
||||
|
||||
#define DEBUG_LEVEL SEVERITY_LOW
|
||||
// SEVERITY_LOW
|
||||
// SEVERITY_MEDIUM
|
||||
// SEVERITY_HIGH
|
||||
// SEVERITY_CRITICAL
|
||||
|
||||
// Different GPS devices,
|
||||
|
||||
#define GPSDEV_DIYMTEK 1
|
||||
#define GPSDEV_DIYUBLOX 2
|
||||
#define GPSDEV_FPUBLOX 3
|
||||
#define GPSDEV_IMU 4
|
||||
#define GPSDEV_NMEA 5
|
||||
|
||||
// Radio Modes, mainly just Mode2
|
||||
#define MODE1 1
|
||||
#define MODE2 2
|
||||
#define MODE3 3
|
||||
#define MODE4 4
|
||||
|
||||
// Frame models
|
||||
#define QUAD 0 // Normal Quad
|
||||
#define QUADCOAX 1 // Quad with double motors as coax
|
||||
#define HEXA 2 // Hexa
|
||||
#define HEXARADIAL 3
|
||||
#define HEXACOAX 4
|
||||
#define OCTO 5
|
||||
|
||||
#define PWM 0
|
||||
#define I2C 1
|
||||
#define UART 2
|
||||
|
||||
|
||||
|
||||
// Following variables stored in EEPROM
|
||||
float KP_QUAD_ROLL;
|
||||
float KI_QUAD_ROLL;
|
||||
float STABLE_MODE_KP_RATE_ROLL;
|
||||
float KP_QUAD_PITCH;
|
||||
float KI_QUAD_PITCH;
|
||||
float STABLE_MODE_KP_RATE_PITCH;
|
||||
float KP_QUAD_YAW;
|
||||
float KI_QUAD_YAW;
|
||||
float STABLE_MODE_KP_RATE_YAW;
|
||||
float STABLE_MODE_KP_RATE; //NOT USED NOW
|
||||
float KP_GPS_ROLL;
|
||||
float KI_GPS_ROLL;
|
||||
float KD_GPS_ROLL;
|
||||
float KP_GPS_PITCH;
|
||||
float KI_GPS_PITCH;
|
||||
float KD_GPS_PITCH;
|
||||
float GPS_MAX_ANGLE;
|
||||
float KP_ALTITUDE;
|
||||
float KI_ALTITUDE;
|
||||
float KD_ALTITUDE;
|
||||
int acc_offset_x;
|
||||
int acc_offset_y;
|
||||
int acc_offset_z;
|
||||
int gyro_offset_roll;
|
||||
int gyro_offset_pitch;
|
||||
int gyro_offset_yaw;
|
||||
float Kp_ROLLPITCH;
|
||||
float Ki_ROLLPITCH;
|
||||
float Kp_YAW;
|
||||
float Ki_YAW;
|
||||
float GEOG_CORRECTION_FACTOR=0;
|
||||
int MAGNETOMETER;
|
||||
float Kp_RateRoll;
|
||||
float Ki_RateRoll;
|
||||
float Kd_RateRoll;
|
||||
float Kp_RatePitch;
|
||||
float Ki_RatePitch;
|
||||
float Kd_RatePitch;
|
||||
float Kp_RateYaw;
|
||||
float Ki_RateYaw;
|
||||
float Kd_RateYaw;
|
||||
float xmitFactor;
|
||||
float ch_roll_slope = 1;
|
||||
float ch_pitch_slope = 1;
|
||||
float ch_throttle_slope = 1;
|
||||
float ch_yaw_slope = 1;
|
||||
float ch_aux_slope = 1;
|
||||
float ch_aux2_slope = 1;
|
||||
float ch_roll_offset = 0;
|
||||
float ch_pitch_offset = 0;
|
||||
float ch_throttle_offset = 0;
|
||||
float ch_yaw_offset = 0;
|
||||
float ch_aux_offset = 0;
|
||||
float ch_aux2_offset = 0;
|
||||
byte cam_mode = 0;
|
||||
byte mag_orientation = 0; // mag variables, reserved for future use, 31-10-10, jp
|
||||
float mag_declination = 0.0;
|
||||
float mag_offset_x = 0; // is int enough for offsets.. checkit, 31-10-10, jp
|
||||
float mag_offset_y = 0;
|
||||
float mag_offset_z = 0;
|
||||
int MIN_THROTTLE;
|
||||
//float eeprom_counter; // reserved for eeprom write counter, 31-10-10, jp
|
||||
//float eeprom_checker; // reserved for eeprom checksums, 01-11-10, jp
|
||||
|
||||
// obstacle avoidance
|
||||
float KP_RF_ROLL;
|
||||
float KD_RF_ROLL;
|
||||
float KI_RF_ROLL;
|
||||
float KP_RF_PITCH;
|
||||
float KD_RF_PITCH;
|
||||
float KI_RF_PITCH;
|
||||
float RF_MAX_ANGLE; // Maximun command roll and pitch angle from obstacle avoiding control
|
||||
float RF_SAFETY_ZONE; // object avoidance will move away from objects within this distance (in cm)
|
||||
|
||||
// sonar for altitude hold
|
||||
float KP_SONAR_ALTITUDE;
|
||||
float KI_SONAR_ALTITUDE;
|
||||
float KD_SONAR_ALTITUDE;
|
||||
|
||||
// This function call contains the default values that are set to the ArduCopter
|
||||
// when a "Default EEPROM Value" command is sent through serial interface
|
||||
void defaultUserConfig() {
|
||||
KP_QUAD_ROLL = 4.0;
|
||||
KI_QUAD_ROLL = 0.15;
|
||||
STABLE_MODE_KP_RATE_ROLL = 1.2;
|
||||
KP_QUAD_PITCH = 4.0;
|
||||
KI_QUAD_PITCH = 0.15;
|
||||
STABLE_MODE_KP_RATE_PITCH = 1.2;
|
||||
KP_QUAD_YAW = 3.0;
|
||||
KI_QUAD_YAW = 0.15;
|
||||
STABLE_MODE_KP_RATE_YAW = 2.4;
|
||||
STABLE_MODE_KP_RATE = 0.2; // NOT USED NOW
|
||||
KP_GPS_ROLL = 0.012; //0.013;
|
||||
KI_GPS_ROLL = 0.001; //0.005;
|
||||
KD_GPS_ROLL = 0.015; //0.012;
|
||||
KP_GPS_PITCH = 0.010; //0.013;
|
||||
KI_GPS_PITCH = 0.001; //0.005;
|
||||
KD_GPS_PITCH = 0.015; //0.01;
|
||||
GPS_MAX_ANGLE = 22;
|
||||
KP_ALTITUDE = 0.08;
|
||||
KI_ALTITUDE = 0.05;
|
||||
KD_ALTITUDE = 0.06;
|
||||
acc_offset_x = 2048;
|
||||
acc_offset_y = 2048;
|
||||
acc_offset_z = 2048;
|
||||
gyro_offset_roll = 1659;
|
||||
gyro_offset_pitch = 1650;
|
||||
gyro_offset_yaw = 1650;
|
||||
Kp_ROLLPITCH = 0.0014;
|
||||
Ki_ROLLPITCH = 0.00000015;
|
||||
Kp_YAW = 1.0;
|
||||
Ki_YAW = 0.00002;
|
||||
GEOG_CORRECTION_FACTOR = 0.0; // will be automatically calculated
|
||||
MAGNETOMETER = 0;
|
||||
Kp_RateRoll = 1.95;
|
||||
Ki_RateRoll = 0.0;
|
||||
Kd_RateRoll = 0.0;
|
||||
Kp_RatePitch = 1.95;
|
||||
Ki_RatePitch = 0.0;
|
||||
Kd_RatePitch = 0.0;
|
||||
Kp_RateYaw = 3.2;
|
||||
Ki_RateYaw = 0.0;
|
||||
Kd_RateYaw = 0.0;
|
||||
xmitFactor = 0.32;
|
||||
roll_mid = 1500;
|
||||
pitch_mid = 1500;
|
||||
yaw_mid = 1500;
|
||||
ch_roll_slope = 1;
|
||||
ch_pitch_slope = 1;
|
||||
ch_throttle_slope = 1;
|
||||
ch_yaw_slope = 1;
|
||||
ch_aux_slope = 1;
|
||||
ch_aux2_slope = 1;
|
||||
ch_roll_offset = 0;
|
||||
ch_pitch_offset = 0;
|
||||
ch_throttle_offset = 0;
|
||||
ch_yaw_offset = 0;
|
||||
ch_aux_offset = 0;
|
||||
ch_aux2_offset = 0;
|
||||
cam_mode = 0;
|
||||
mag_orientation = 0; // reserved for future, 31-10-10, jp
|
||||
mag_declination = 0.0;
|
||||
mag_offset_x = 0;
|
||||
mag_offset_y = 0;
|
||||
mag_offset_z = 0;
|
||||
MIN_THROTTLE = 1040; // used to be #define but now in EEPROM
|
||||
KP_RF_ROLL = 0.10;
|
||||
KI_RF_ROLL = 0.00;
|
||||
KD_RF_ROLL = 0.03;
|
||||
KP_RF_PITCH = 0.10;
|
||||
KI_RF_PITCH = 0.00;
|
||||
KD_RF_PITCH = 0.03;
|
||||
RF_MAX_ANGLE = 10.0;
|
||||
RF_SAFETY_ZONE = 120.0; // object avoidance will avoid objects within this range (in cm)
|
||||
KP_SONAR_ALTITUDE = 0.8;
|
||||
KI_SONAR_ALTITUDE = 0.3;
|
||||
KD_SONAR_ALTITUDE = 0.7;
|
||||
}
|
||||
|
||||
// EEPROM storage addresses
|
||||
#define KP_QUAD_ROLL_ADR 0
|
||||
#define KI_QUAD_ROLL_ADR 8
|
||||
#define STABLE_MODE_KP_RATE_ROLL_ADR 4
|
||||
#define KP_QUAD_PITCH_ADR 12
|
||||
#define KI_QUAD_PITCH_ADR 20
|
||||
#define STABLE_MODE_KP_RATE_PITCH_ADR 16
|
||||
#define KP_QUAD_YAW_ADR 24
|
||||
#define KI_QUAD_YAW_ADR 32
|
||||
#define STABLE_MODE_KP_RATE_YAW_ADR 28
|
||||
#define STABLE_MODE_KP_RATE_ADR 36 // NOT USED NOW
|
||||
#define KP_GPS_ROLL_ADR 40
|
||||
#define KI_GPS_ROLL_ADR 48
|
||||
#define KD_GPS_ROLL_ADR 44
|
||||
#define KP_GPS_PITCH_ADR 52
|
||||
#define KI_GPS_PITCH_ADR 60
|
||||
#define KD_GPS_PITCH_ADR 56
|
||||
#define GPS_MAX_ANGLE_ADR 64
|
||||
#define KP_ALTITUDE_ADR 68
|
||||
#define KI_ALTITUDE_ADR 76
|
||||
#define KD_ALTITUDE_ADR 72
|
||||
#define acc_offset_x_ADR 80
|
||||
#define acc_offset_y_ADR 84
|
||||
#define acc_offset_z_ADR 88
|
||||
#define gyro_offset_roll_ADR 92
|
||||
#define gyro_offset_pitch_ADR 96
|
||||
#define gyro_offset_yaw_ADR 100
|
||||
#define Kp_ROLLPITCH_ADR 104
|
||||
#define Ki_ROLLPITCH_ADR 108
|
||||
#define Kp_YAW_ADR 112
|
||||
#define Ki_YAW_ADR 116
|
||||
#define GEOG_CORRECTION_FACTOR_ADR 120
|
||||
#define MAGNETOMETER_ADR 124
|
||||
#define XMITFACTOR_ADR 128
|
||||
#define KP_RATEROLL_ADR 132
|
||||
#define KI_RATEROLL_ADR 136
|
||||
#define KD_RATEROLL_ADR 140
|
||||
#define KP_RATEPITCH_ADR 144
|
||||
#define KI_RATEPITCH_ADR 148
|
||||
#define KD_RATEPITCH_ADR 152
|
||||
#define KP_RATEYAW_ADR 156
|
||||
#define KI_RATEYAW_ADR 160
|
||||
#define KD_RATEYAW_ADR 164
|
||||
#define CHROLL_MID 168
|
||||
#define CHPITCH_MID 172
|
||||
#define CHYAW_MID 176
|
||||
#define ch_roll_slope_ADR 180
|
||||
#define ch_pitch_slope_ADR 184
|
||||
#define ch_throttle_slope_ADR 188
|
||||
#define ch_yaw_slope_ADR 192
|
||||
#define ch_aux_slope_ADR 196
|
||||
#define ch_aux2_slope_ADR 200
|
||||
#define ch_roll_offset_ADR 204
|
||||
#define ch_pitch_offset_ADR 208
|
||||
#define ch_throttle_offset_ADR 212
|
||||
#define ch_yaw_offset_ADR 216
|
||||
#define ch_aux_offset_ADR 220
|
||||
#define ch_aux2_offset_ADR 224
|
||||
#define cam_mode_ADR 228
|
||||
#define mag_orientation_ADR 232 // reserved for future, 31-10-10, jp
|
||||
#define mag_declination_ADR 236 // reserved for future, 31-10-10, jp
|
||||
#define mag_offset_x_ADR 240
|
||||
#define mag_offset_y_ADR 244
|
||||
#define mag_offset_z_ADR 248
|
||||
#define MIN_THROTTLE_ADR 252
|
||||
#define KP_RF_ROLL_ADR 256
|
||||
#define KI_RF_ROLL_ADR 260
|
||||
#define KD_RF_ROLL_ADR 264
|
||||
#define KP_RF_PITCH_ADR 268
|
||||
#define KI_RF_PITCH_ADR 272
|
||||
#define KD_RF_PITCH_ADR 276
|
||||
#define RF_MAX_ANGLE_ADR 280
|
||||
#define RF_SAFETY_ZONE_ADR 284
|
||||
#define KP_SONAR_ALTITUDE_ADR 288
|
||||
#define KI_SONAR_ALTITUDE_ADR 292
|
||||
#define KD_SONAR_ALTITUDE_ADR 296
|
||||
|
||||
//#define eeprom_counter_ADR 238 // hmm should i move these?!? , 31-10-10, jp
|
||||
//#define eeprom_checker_ADR 240 // this too... , 31-10-10, jp
|
||||
|
||||
|
||||
|
||||
// end of file
|
@ -1,629 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : ArducopterNG.pde
|
||||
Version : v1.0, 11 October 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (AeroQuad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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/>.
|
||||
|
||||
/* ********************************************************************** */
|
||||
/* Hardware : ArduPilot Mega + Sensor Shield (Production versions) */
|
||||
/* Mounting position : RC connectors pointing backwards */
|
||||
/* This code use this libraries : */
|
||||
/* APM_RC : Radio library (with InstantPWM) */
|
||||
/* AP_ADC : External ADC library */
|
||||
/* DataFlash : DataFlash log library */
|
||||
/* APM_BMP085 : BMP085 barometer library */
|
||||
/* AP_Compass : HMC5843 compass library [optional] */
|
||||
/* GPS_MTK or GPS_UBLOX or GPS_NMEA : GPS library [optional] */
|
||||
/* ********************************************************************** */
|
||||
|
||||
/* ************************************************************ */
|
||||
/* **************** MAIN PROGRAM - MODULES ******************** */
|
||||
/* ************************************************************ */
|
||||
|
||||
/* ************************************************************ */
|
||||
// User MODULES
|
||||
//
|
||||
// Please check your modules settings for every new software downloads you have.
|
||||
// Also check repository / ArduCopter wiki pages for ChangeLogs and software notes
|
||||
//
|
||||
// Comment out with // modules that you are not using
|
||||
//
|
||||
// Do check ArduUser.h settings file too !!
|
||||
//
|
||||
///////////////////////////////////////
|
||||
// Modules Config
|
||||
// --------------------------
|
||||
|
||||
#define IsGPS // Do we have a GPS connected
|
||||
#define IsNEWMTEK // Do we have MTEK with new firmware
|
||||
#define IsMAG // Do we have a Magnetometer connected, if have remember to activate it from Configurator
|
||||
//#define IsAM // Do we have motormount LED's. AM = Atraction Mode
|
||||
//#define IsCAM // Do we have camera stabilization in use, If you activate, check OUTPUT pins from ArduUser.h
|
||||
|
||||
//#define UseAirspeed // Quads don't use AirSpeed... Legacy, jp 19-10-10
|
||||
#define UseBMP // Use pressure sensor
|
||||
//#define BATTERY_EVENT 1 // (boolean) 0 = don't read battery, 1 = read battery voltage (only if you have it _wired_ up!)
|
||||
//#define IsSONAR // are we using a Sonar for altitude hold? use this or "UseBMP" not both!
|
||||
//#define IsRANGEFINDER // are we using range finders for obstacle avoidance?
|
||||
|
||||
#define CONFIGURATOR
|
||||
|
||||
///////////////////////////////////////
|
||||
// GPS Selection
|
||||
|
||||
#define GPSDEVICE GPSDEV_DIYMTEK // For DIY Drones MediaTek
|
||||
//#define GPSDEVICE GPSDEV_DIYUBLOX // For DIY Drones uBlox GPS
|
||||
//#define GPSDEVICE GPSDEV_FPUBLOX // For Fah Pah Special ArduCopter GPS
|
||||
//#define GPSDEVICE GPSDEV_NMEA // For general NMEA compatible GPSEs
|
||||
//#dedine GPSDEVICE GPSDEV_IMU // For IMU Simulations only
|
||||
|
||||
|
||||
////////////////////////////////////////
|
||||
// Frame / Motor / ESC definitions
|
||||
|
||||
// Introducing new frame / Motor / ESC definitions for future expansion. Currently these are not in
|
||||
// use but they need to be here so implementation work can continue.
|
||||
|
||||
// New frame model definitions. (not in use yet, 28-11-10 jp)
|
||||
#define FRAME_MODEL QUAD // Quad frame model
|
||||
//#define FRAME_MODEL HEXA // Quad frame model
|
||||
//#define FRAME_MODEL OCTO // Quad frame model
|
||||
|
||||
|
||||
// New motor definition for different frame type (not in use yet, 28-11-10 jp)
|
||||
#define MAX_MOTORS 4 // Are we using more motors than 4, possible choises are 4, 6, 8
|
||||
// This has to be on main .pde to get included on all other header etc files
|
||||
|
||||
// Not in use yet, 28-11-10 jp
|
||||
#define MOTORTYPE PWM // Traditional PWM ESC's controlling motors
|
||||
//#define MOTORTYPE I2C // I2C style ESC's controlling motors
|
||||
//#define MOTORTYPE UART // UART style ESC's controlling motors
|
||||
|
||||
|
||||
|
||||
|
||||
////////////////////
|
||||
// Serial ports & speeds
|
||||
|
||||
// Serial data, do we have FTDI cable or Xbee on Telemetry port as our primary command link
|
||||
// If we are using normal FTDI/USB port as our telemetry/configuration, keep next line disabled
|
||||
//#define SerXbee
|
||||
|
||||
// Telemetry port speed, default is 115200
|
||||
//#define SerBau 19200
|
||||
//#define SerBau 38400
|
||||
//#define SerBau 57600
|
||||
#define SerBau 115200
|
||||
|
||||
|
||||
// For future use, for now don't activate any!
|
||||
// Serial1 speed for GPS, mostly 38.4k, done from libraries
|
||||
//#define GpsBau 19200
|
||||
//#define GpsBau 38400
|
||||
//#define GpsBau 57600
|
||||
//#define GpsBau 115200
|
||||
|
||||
|
||||
/* ************************************************* */
|
||||
// Radio modes
|
||||
#define RADIOMODE MODE2 // Most users have this eg: left stick: Throttle/Rudder, right stick: Elevator/Aileron
|
||||
//#define RADIOMODE MODE1 // Only if you are sure that you have Mode 1 radio.
|
||||
|
||||
// NOTE! MODE1 is not working yet, we need to have input from users to be sure of channel orders. 03-11-10, jp
|
||||
|
||||
|
||||
|
||||
/* ************************************************* */
|
||||
// Flight & Electronics orientation
|
||||
|
||||
// Frame build condiguration
|
||||
//#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
|
||||
//#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
|
||||
// 19-10-10 by JP
|
||||
|
||||
// This feature has been disabled for now, if you want to change between flight orientations
|
||||
// just use DIP switch for that. DIP1 down = X, DIP1 up = +
|
||||
|
||||
// Magneto orientation and corrections.
|
||||
// If you don't have magneto activated, It is safe to ignore these
|
||||
//#ifdef IsMAG
|
||||
//#define MAGORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_FORWARD // This is default solution for ArduCopter
|
||||
//#define MAGORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_BACK // Alternative orientation for ArduCopter
|
||||
#define MAGORIENTATION AP_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 -27.50,23.00,81.00
|
||||
|
||||
// Obsolete, Magnetometer offset are moved to CLI
|
||||
|
||||
// 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
|
||||
// 37 / 60 = 0.61 and for Helsinki it would be 7°44' eg 7. and then 44/60 = 0.73 so declination for Helsinki/South Finland would be 7.73
|
||||
|
||||
// East values are positive
|
||||
// West values are negative
|
||||
|
||||
// Some of devel team's Declinations and their Cities
|
||||
//#define DECLINATION 0.61 // Jani, Bangkok, 0°37' E (Due I live almost at Equator, my Declination is rather small)
|
||||
//#define DECLINATION 7.73 // Jani, Helsinki,7°44' E (My "summer" home back at Finland)
|
||||
//#define DECLINATION -20.68 // Sandro, Belo Horizonte, 22°08' W (Whoah... Sandro is really DECLINED)
|
||||
//#define DECLINATION 7.03 // Randy, Tokyo, 7°02'E
|
||||
//#define DECLINATION 8.91 // Doug, Denver, 8°55'E
|
||||
//#define DECLINATION -6.08 // Jose, Canary Islands, 6°5'W
|
||||
//#define DECLINATION 0.73 // Tony, Minneapolis, 0°44'E
|
||||
|
||||
//#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/* ************************************************************ */
|
||||
/* **************** MAIN PROGRAM - INCLUDES ******************* */
|
||||
/* ************************************************************ */
|
||||
|
||||
//#include <AP_GPS.h>
|
||||
#include <avr/io.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <math.h>
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
|
||||
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <Wire.h> // I2C Communication library
|
||||
#include <EEPROM.h> // EEPROM
|
||||
#include <AP_RangeFinder.h> // RangeFinders (Sonars, IR Sensors)
|
||||
//#include <AP_GPS.h>
|
||||
#include "Arducopter.h"
|
||||
#include "ArduUser.h"
|
||||
|
||||
#ifdef IsGPS
|
||||
// GPS library (Include only one library)
|
||||
#include <GPS_MTK.h> // ArduPilot MTK GPS Library
|
||||
//#include <GPS_IMU.h> // ArduPilot IMU/SIM GPS Library
|
||||
//#include <GPS_UBLOX.h> // ArduPilot Ublox GPS Library
|
||||
//#include <GPS_NMEA.h> // ArduPilot NMEA GPS library
|
||||
#endif
|
||||
|
||||
#if AIRFRAME == HELI
|
||||
#include "Heli.h"
|
||||
#endif
|
||||
|
||||
/* Software version */
|
||||
#define VER 1.54 // Current software version (only numeric values)
|
||||
|
||||
// Sensors - declare one global instance
|
||||
AP_ADC_ADS7844 adc;
|
||||
APM_BMP085_Class APM_BMP085;
|
||||
AP_Compass_HMC5843 AP_Compass;
|
||||
#ifdef IsSONAR
|
||||
AP_RangeFinder_MaxsonarXL AP_RangeFinder_down; // Default sonar for altitude hold
|
||||
//AP_RangeFinder_MaxsonarLV AP_RangeFinder_down; // Alternative sonar is AP_RangeFinder_MaxsonarLV
|
||||
#endif
|
||||
#ifdef IsRANGEFINDER
|
||||
AP_RangeFinder_MaxsonarLV AP_RangeFinder_frontRight;
|
||||
AP_RangeFinder_MaxsonarLV AP_RangeFinder_backRight;
|
||||
AP_RangeFinder_MaxsonarLV AP_RangeFinder_backLeft;
|
||||
AP_RangeFinder_MaxsonarLV AP_RangeFinder_frontLeft;
|
||||
#endif
|
||||
|
||||
/* ************************************************************ */
|
||||
/* ************* MAIN PROGRAM - DECLARATIONS ****************** */
|
||||
/* ************************************************************ */
|
||||
|
||||
byte flightMode;
|
||||
|
||||
unsigned long currentTime; // current time in milliseconds
|
||||
unsigned long currentTimeMicros = 0, previousTimeMicros = 0; // current and previous loop time in microseconds
|
||||
unsigned long mainLoop = 0;
|
||||
unsigned long mediumLoop = 0;
|
||||
unsigned long slowLoop = 0;
|
||||
|
||||
/* ************************************************************ */
|
||||
/* **************** MAIN PROGRAM - SETUP ********************** */
|
||||
/* ************************************************************ */
|
||||
void setup() {
|
||||
|
||||
APM_Init(); // APM Hardware initialization (in System.pde)
|
||||
|
||||
mainLoop = millis(); // Initialize timers
|
||||
mediumLoop = mainLoop;
|
||||
GPS_timer = mainLoop;
|
||||
motorArmed = 0;
|
||||
|
||||
GEOG_CORRECTION_FACTOR = 0; // Geographic correction factor will be automatically calculated
|
||||
|
||||
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...
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************ */
|
||||
/* ************** MAIN PROGRAM - MAIN LOOP ******************** */
|
||||
/* ************************************************************ */
|
||||
|
||||
// Sensor reading loop is inside AP_ADC and runs at 400Hz (based on Timer2 interrupt)
|
||||
|
||||
// * fast rate loop => Main loop => 200Hz
|
||||
// read sensors
|
||||
// IMU : update attitude
|
||||
// motor control
|
||||
// Asyncronous task : read transmitter
|
||||
// * medium rate loop (60Hz)
|
||||
// Asyncronous task : read GPS
|
||||
// * slow rate loop (10Hz)
|
||||
// magnetometer
|
||||
// barometer (20Hz)
|
||||
// sonar (20Hz)
|
||||
// obstacle avoidance (20Hz)
|
||||
// external command/telemetry
|
||||
// Battery monitor
|
||||
|
||||
|
||||
|
||||
/* ***************************************************** */
|
||||
// Main loop
|
||||
void loop()
|
||||
{
|
||||
|
||||
currentTimeMicros = micros();
|
||||
currentTime = currentTimeMicros / 1000;
|
||||
|
||||
// Main loop at 200Hz (IMU + control)
|
||||
if ((currentTime-mainLoop) > 5) // about 200Hz (every 5ms)
|
||||
{
|
||||
G_Dt = (currentTimeMicros-previousTimeMicros) * 0.000001; // Microseconds!!!
|
||||
mainLoop = currentTime;
|
||||
previousTimeMicros = currentTimeMicros;
|
||||
|
||||
//IMU DCM Algorithm
|
||||
Read_adc_raw(); // Read sensors raw data
|
||||
Matrix_update();
|
||||
Normalize();
|
||||
Drift_correction();
|
||||
Euler_angles();
|
||||
|
||||
// Read radio values (if new data is available)
|
||||
if (APM_RC.GetState() == 1) { // New radio frame?
|
||||
#if AIRFRAME == QUAD
|
||||
read_radio();
|
||||
#endif
|
||||
#if AIRFRAME == HELI
|
||||
heli_read_radio();
|
||||
#endif
|
||||
}
|
||||
|
||||
// Attitude control
|
||||
if(flightMode == STABLE_MODE) { // STABLE Mode
|
||||
gled_speed = 1200;
|
||||
if (AP_mode == AP_NORMAL_MODE) { // Normal mode
|
||||
#if AIRFRAME == QUAD
|
||||
Attitude_control_v3(command_rx_roll,command_rx_pitch,command_rx_yaw);
|
||||
#endif
|
||||
#if AIRFRAME == HELI
|
||||
heli_attitude_control(command_rx_roll,command_rx_pitch,command_rx_collective,command_rx_yaw);
|
||||
#endif
|
||||
}else{ // Automatic mode : GPS position hold mode
|
||||
#if AIRFRAME == QUAD
|
||||
Attitude_control_v3(command_rx_roll+command_gps_roll+command_RF_roll,command_rx_pitch+command_gps_pitch+command_RF_pitch,command_rx_yaw);
|
||||
#endif
|
||||
#if AIRFRAME == HELI
|
||||
heli_attitude_control(command_rx_roll+command_gps_roll,command_rx_pitch+command_gps_pitch,command_rx_collective,command_rx_yaw);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else { // ACRO Mode
|
||||
gled_speed = 400;
|
||||
Rate_control_v2();
|
||||
// Reset yaw, so if we change to stable mode we continue with the actual yaw direction
|
||||
command_rx_yaw = ToDeg(yaw);
|
||||
}
|
||||
|
||||
// Send output commands to motor ESCs...
|
||||
#if AIRFRAME == QUAD // we update the heli swashplate at about 60hz
|
||||
motor_output();
|
||||
#endif
|
||||
|
||||
#ifdef IsCAM
|
||||
// Do we have cameras stabilization connected and in use?
|
||||
if(!SW_DIP2) camera_output();
|
||||
#endif
|
||||
|
||||
// Autopilot mode functions - GPS Hold, Altitude Hold + object avoidance
|
||||
if (AP_mode == AP_AUTOMATIC_MODE)
|
||||
{
|
||||
digitalWrite(LED_Yellow,HIGH); // Yellow LED ON : GPS Position Hold MODE
|
||||
|
||||
// Do GPS Position hold (lattitude & longitude)
|
||||
if (target_position)
|
||||
{
|
||||
#ifdef IsGPS
|
||||
if (GPS.NewData) // New GPS info?
|
||||
{
|
||||
if (GPS.Fix)
|
||||
{
|
||||
read_GPS_data(); // In Navigation.pde
|
||||
//Position_control(target_lattitude,target_longitude); // Call GPS position hold routine
|
||||
Position_control_v2(target_lattitude,target_longitude); // V2 of GPS Position holdCall GPS position hold routine
|
||||
}else{
|
||||
command_gps_roll=0;
|
||||
command_gps_pitch=0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
} else { // First time we enter in GPS position hold we capture the target position as the actual position
|
||||
#ifdef IsGPS
|
||||
if (GPS.Fix){ // We need a GPS Fix to capture the actual position...
|
||||
target_lattitude = GPS.Lattitude;
|
||||
target_longitude = GPS.Longitude;
|
||||
target_position=1;
|
||||
}
|
||||
#endif
|
||||
command_gps_roll=0;
|
||||
command_gps_pitch=0;
|
||||
Reset_I_terms_navigation(); // Reset I terms (in Navigation.pde)
|
||||
}
|
||||
|
||||
// Switch on altitude control if we have a barometer or Sonar
|
||||
#if (defined(UseBMP) || defined(IsSONAR))
|
||||
if( altitude_control_method == ALTITUDE_CONTROL_NONE )
|
||||
{
|
||||
// by default turn on altitude hold using barometer
|
||||
#ifdef UseBMP
|
||||
if( press_baro_altitude != 0 )
|
||||
{
|
||||
altitude_control_method = ALTITUDE_CONTROL_BARO;
|
||||
target_baro_altitude = press_baro_altitude;
|
||||
baro_altitude_I = 0; // don't carry over any I values from previous times user may have switched on altitude control
|
||||
}
|
||||
#endif
|
||||
|
||||
// use sonar if it's available
|
||||
#ifdef IsSONAR
|
||||
if( sonar_status == SONAR_STATUS_OK && press_sonar_altitude != 0 )
|
||||
{
|
||||
altitude_control_method = ALTITUDE_CONTROL_SONAR;
|
||||
target_sonar_altitude = constrain(press_sonar_altitude,AP_RangeFinder_down.min_distance*3,sonar_threshold);
|
||||
}
|
||||
sonar_altitude_I = 0; // don't carry over any I values from previous times user may have switched on altitude control
|
||||
#endif
|
||||
|
||||
// capture current throttle to use as base for altitude control
|
||||
initial_throttle = ch_throttle;
|
||||
ch_throttle_altitude_hold = ch_throttle;
|
||||
}
|
||||
|
||||
// Sonar Altitude Control
|
||||
#ifdef IsSONAR
|
||||
if( sonar_new_data ) // if new sonar data has arrived
|
||||
{
|
||||
// Allow switching between sonar and barometer
|
||||
#ifdef UseBMP
|
||||
|
||||
// if SONAR become invalid switch to barometer
|
||||
if( altitude_control_method == ALTITUDE_CONTROL_SONAR && sonar_valid_count <= -3 )
|
||||
{
|
||||
// next target barometer altitude to current barometer altitude + user's desired change over last sonar altitude (i.e. keeps up the momentum)
|
||||
altitude_control_method = ALTITUDE_CONTROL_BARO;
|
||||
target_baro_altitude = press_baro_altitude;// + constrain((target_sonar_altitude - press_sonar_altitude),-50,50);
|
||||
}
|
||||
|
||||
// if SONAR becomes valid switch to sonar control
|
||||
if( altitude_control_method == ALTITUDE_CONTROL_BARO && sonar_valid_count >= 3 )
|
||||
{
|
||||
altitude_control_method = ALTITUDE_CONTROL_SONAR;
|
||||
if( target_sonar_altitude == 0 ) { // if target sonar altitude hasn't been intialised before..
|
||||
target_sonar_altitude = press_sonar_altitude;// + constrain((target_baro_altitude - press_baro_altitude),-50,50); // maybe this should just use the user's last valid target sonar altitude
|
||||
}
|
||||
// ensure target altitude is reasonable
|
||||
target_sonar_altitude = constrain(target_sonar_altitude,AP_RangeFinder_down.min_distance*3,sonar_threshold);
|
||||
}
|
||||
#endif // defined(UseBMP)
|
||||
|
||||
// main Sonar control
|
||||
if( altitude_control_method == ALTITUDE_CONTROL_SONAR )
|
||||
{
|
||||
if( sonar_status == SONAR_STATUS_OK ) {
|
||||
ch_throttle_altitude_hold = Altitude_control_Sonar(press_sonar_altitude,target_sonar_altitude); // calculate throttle to maintain altitude
|
||||
} else {
|
||||
// if sonar_altitude becomes invalid we return control to user temporarily
|
||||
ch_throttle_altitude_hold = ch_throttle;
|
||||
}
|
||||
|
||||
// modify the target altitude if user moves stick more than 100 up or down
|
||||
if( abs(ch_throttle-initial_throttle)>100 )
|
||||
{
|
||||
target_sonar_altitude += (ch_throttle-initial_throttle)/25;
|
||||
if( target_sonar_altitude < AP_RangeFinder_down.min_distance*3 )
|
||||
target_sonar_altitude = AP_RangeFinder_down.min_distance*3;
|
||||
#if !defined(UseBMP) // limit the upper altitude if no barometer used
|
||||
if( target_sonar_altitude > sonar_threshold)
|
||||
target_sonar_altitude = sonar_threshold;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
sonar_new_data = 0; // record that we've consumed the sonar data
|
||||
} // new sonar data
|
||||
#endif // #ifdef IsSONAR
|
||||
|
||||
// Barometer Altitude control
|
||||
#ifdef UseBMP
|
||||
if( baro_new_data && altitude_control_method == ALTITUDE_CONTROL_BARO ) // New altitude data?
|
||||
{
|
||||
ch_throttle_altitude_hold = Altitude_control_baro(press_baro_altitude,target_baro_altitude); // calculate throttle to maintain altitude
|
||||
baro_new_data=0; // record that we have consumed the new data
|
||||
|
||||
// modify the target altitude if user moves stick more than 100 up or down
|
||||
if (abs(ch_throttle-initial_throttle)>100)
|
||||
{
|
||||
target_baro_altitude += (ch_throttle-initial_throttle)/25; // Change in stick position => altitude ascend/descend rate control
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif // defined(UseBMP) || defined(IsSONAR)
|
||||
|
||||
// Object avoidance
|
||||
#ifdef IsRANGEFINDER
|
||||
if( RF_new_data )
|
||||
{
|
||||
Obstacle_avoidance(RF_SAFETY_ZONE); // main obstacle avoidance function
|
||||
RF_new_data = 0; // record that we have consumed the rangefinder data
|
||||
}
|
||||
#endif
|
||||
}else{
|
||||
digitalWrite(LED_Yellow,LOW);
|
||||
target_position=0;
|
||||
if( altitude_control_method != ALTITUDE_CONTROL_NONE )
|
||||
{
|
||||
altitude_control_method = ALTITUDE_CONTROL_NONE; // turn off altitude control
|
||||
}
|
||||
} // if (AP_mode == AP_AUTOMATIC_MODE)
|
||||
}
|
||||
|
||||
// Medium loop (about 60Hz)
|
||||
if ((currentTime-mediumLoop)>=17){
|
||||
mediumLoop = currentTime;
|
||||
#ifdef IsGPS
|
||||
GPS.Read(); // Read GPS data
|
||||
#endif
|
||||
|
||||
#if AIRFRAME == HELI
|
||||
// Send output commands to heli swashplate...
|
||||
heli_moveSwashPlate();
|
||||
#endif
|
||||
|
||||
// Each of the six cases executes at 10Hz
|
||||
switch (medium_loopCounter){
|
||||
case 0: // Magnetometer reading (10Hz)
|
||||
medium_loopCounter++;
|
||||
slowLoop++;
|
||||
#ifdef IsMAG
|
||||
if (MAGNETOMETER == 1) {
|
||||
AP_Compass.read(); // Read magnetometer
|
||||
AP_Compass.calculate(roll,pitch); // Calculate heading
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case 1: // Barometer + RangeFinder reading (2x10Hz = 20Hz)
|
||||
medium_loopCounter++;
|
||||
#ifdef UseBMP
|
||||
if (APM_BMP085.Read()){
|
||||
read_baro();
|
||||
baro_new_data = 1;
|
||||
}
|
||||
#endif
|
||||
#ifdef IsSONAR
|
||||
read_Sonar();
|
||||
sonar_new_data = 1; // process sonar values at 20Hz
|
||||
#endif
|
||||
#ifdef IsRANGEFINDER
|
||||
read_RF_Sensors();
|
||||
RF_new_data = 1;
|
||||
#endif
|
||||
break;
|
||||
case 2: // Send serial telemetry (10Hz)
|
||||
medium_loopCounter++;
|
||||
#ifdef CONFIGURATOR
|
||||
sendSerialTelemetry();
|
||||
#endif
|
||||
break;
|
||||
case 3: // Read serial telemetry (10Hz)
|
||||
medium_loopCounter++;
|
||||
#ifdef CONFIGURATOR
|
||||
readSerialCommand();
|
||||
#endif
|
||||
break;
|
||||
case 4: // second Barometer + RangeFinder reading (2x10Hz = 20Hz)
|
||||
medium_loopCounter++;
|
||||
#ifdef UseBMP
|
||||
if (APM_BMP085.Read()){
|
||||
read_baro();
|
||||
baro_new_data = 1;
|
||||
}
|
||||
#endif
|
||||
#ifdef IsSONAR
|
||||
read_Sonar();
|
||||
sonar_new_data = 1; // process sonar values at 20Hz
|
||||
#endif
|
||||
#ifdef IsRANGEFINDER
|
||||
read_RF_Sensors();
|
||||
RF_new_data = 1;
|
||||
#endif
|
||||
break;
|
||||
case 5: // Battery monitor (10Hz)
|
||||
medium_loopCounter=0;
|
||||
#if BATTERY_EVENT == 1
|
||||
read_battery(); // Battery monitor
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// AM and Mode status LED lights
|
||||
if(millis() - gled_timer > gled_speed) {
|
||||
gled_timer = millis();
|
||||
if(gled_status == HIGH) {
|
||||
digitalWrite(LED_Green, LOW);
|
||||
#ifdef IsAM
|
||||
digitalWrite(RE_LED, LOW);
|
||||
#endif
|
||||
gled_status = LOW;
|
||||
// SerPrln("L");
|
||||
}
|
||||
else {
|
||||
digitalWrite(LED_Green, HIGH);
|
||||
#ifdef IsAM
|
||||
if(motorArmed) digitalWrite(RE_LED, HIGH);
|
||||
#endif
|
||||
gled_status = HIGH;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
@ -1,176 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Attitude.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
/* ************************************************************ */
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
// Function : Attitude_control_v3()
|
||||
//
|
||||
// Stable flight mode main algoritms
|
||||
//
|
||||
// Parameters:
|
||||
// - none
|
||||
//
|
||||
// Returns : - none
|
||||
//
|
||||
// Alters :
|
||||
// err_roll, roll_rate
|
||||
//
|
||||
// Relies :
|
||||
// Radio input, Gyro
|
||||
//
|
||||
|
||||
/* ************************************************************ */
|
||||
// STABLE MODE
|
||||
// PI absolute angle control driving a P rate control
|
||||
// Input : desired Roll, Pitch and Yaw absolute angles. Output : Motor commands
|
||||
void Attitude_control_v3(int command_roll, int command_pitch, int command_yaw)
|
||||
{
|
||||
#define MAX_CONTROL_OUTPUT 250
|
||||
float stable_roll,stable_pitch,stable_yaw;
|
||||
|
||||
// ROLL CONTROL
|
||||
err_roll = command_roll - ToDeg(roll);
|
||||
err_roll = constrain(err_roll,-25,25); // to limit max roll command...
|
||||
|
||||
roll_I += err_roll*G_Dt;
|
||||
roll_I = constrain(roll_I,-20,20);
|
||||
|
||||
// PID absolute angle control
|
||||
stable_roll = KP_QUAD_ROLL*err_roll + KI_QUAD_ROLL*roll_I;
|
||||
|
||||
// PD rate control (we use also the bias corrected gyro rates)
|
||||
err_roll = stable_roll - ToDeg(Omega[0]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected
|
||||
control_roll = STABLE_MODE_KP_RATE_ROLL*err_roll;
|
||||
control_roll = constrain(control_roll,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT);
|
||||
|
||||
// PITCH CONTROL
|
||||
err_pitch = command_pitch - ToDeg(pitch);
|
||||
err_pitch = constrain(err_pitch,-25,25); // to limit max pitch command...
|
||||
|
||||
pitch_I += err_pitch*G_Dt;
|
||||
pitch_I = constrain(pitch_I,-20,20);
|
||||
|
||||
// PID absolute angle control
|
||||
stable_pitch = KP_QUAD_PITCH*err_pitch + KI_QUAD_PITCH*pitch_I;
|
||||
|
||||
// P rate control (we use also the bias corrected gyro rates)
|
||||
err_pitch = stable_pitch - ToDeg(Omega[1]);
|
||||
control_pitch = STABLE_MODE_KP_RATE_PITCH*err_pitch;
|
||||
control_pitch = constrain(control_pitch,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT);
|
||||
|
||||
// YAW CONTROL
|
||||
err_yaw = command_yaw - ToDeg(yaw);
|
||||
if (err_yaw > 180) // Normalize to -180,180
|
||||
err_yaw -= 360;
|
||||
else if(err_yaw < -180)
|
||||
err_yaw += 360;
|
||||
err_yaw = constrain(err_yaw,-60,60); // to limit max yaw command...
|
||||
|
||||
yaw_I += err_yaw*G_Dt;
|
||||
yaw_I = constrain(yaw_I,-20,20);
|
||||
|
||||
// PID absoulte angle control
|
||||
stable_yaw = KP_QUAD_YAW*err_yaw + KI_QUAD_YAW*yaw_I;
|
||||
// PD rate control (we use also the bias corrected gyro rates)
|
||||
err_yaw = stable_yaw - ToDeg(Omega[2]);
|
||||
control_yaw = STABLE_MODE_KP_RATE_YAW*err_yaw;
|
||||
control_yaw = constrain(control_yaw,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT);
|
||||
}
|
||||
|
||||
// ACRO MODE
|
||||
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
// Function : Rate_control()
|
||||
//
|
||||
// Acro mode main algoritms
|
||||
//
|
||||
// Parameters:
|
||||
// - none
|
||||
//
|
||||
// Returns : - none
|
||||
//
|
||||
// Alters :
|
||||
// err_roll, roll_rate
|
||||
//
|
||||
// Relies :
|
||||
// Radio input, Gyro
|
||||
//
|
||||
|
||||
|
||||
// ACRO MODE
|
||||
void Rate_control_v2()
|
||||
{
|
||||
static float previousRollRate, previousPitchRate, previousYawRate;
|
||||
float currentRollRate, currentPitchRate, currentYawRate;
|
||||
|
||||
// ROLL CONTROL
|
||||
currentRollRate = ToDeg(Omega[0]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected
|
||||
err_roll = ((ch_roll- roll_mid) * xmitFactor) - currentRollRate;
|
||||
roll_I += err_roll*G_Dt;
|
||||
roll_I = constrain(roll_I,-20,20);
|
||||
roll_D = (currentRollRate - previousRollRate)/G_Dt;
|
||||
previousRollRate = currentRollRate;
|
||||
// PID control
|
||||
control_roll = Kp_RateRoll*err_roll + Kd_RateRoll*roll_D + Ki_RateRoll*roll_I;
|
||||
|
||||
// PITCH CONTROL
|
||||
currentPitchRate = ToDeg(Omega[1]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected
|
||||
err_pitch = ((ch_pitch - pitch_mid) * xmitFactor) - currentPitchRate;
|
||||
|
||||
pitch_I += err_pitch*G_Dt;
|
||||
pitch_I = constrain(pitch_I,-20,20);
|
||||
|
||||
pitch_D = (currentPitchRate - previousPitchRate)/G_Dt;
|
||||
previousPitchRate = currentPitchRate;
|
||||
|
||||
// PID control
|
||||
control_pitch = Kp_RatePitch*err_pitch + Kd_RatePitch*pitch_D + Ki_RatePitch*pitch_I;
|
||||
|
||||
// YAW CONTROL
|
||||
currentYawRate = ToDeg(Omega[2]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected;
|
||||
err_yaw = ((ch_yaw - yaw_mid)* xmitFactor) - currentYawRate;
|
||||
|
||||
yaw_I += err_yaw*G_Dt;
|
||||
yaw_I = constrain(yaw_I,-20,20);
|
||||
|
||||
yaw_D = (currentYawRate - previousYawRate)/G_Dt;
|
||||
previousYawRate = currentYawRate;
|
||||
|
||||
// PID control
|
||||
control_yaw = Kp_RateYaw*err_yaw + Kd_RateYaw*yaw_D + Ki_RateYaw*yaw_I;
|
||||
}
|
||||
|
@ -1,741 +0,0 @@
|
||||
/*
|
||||
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,
|
||||
Ken McEwans, Roberto Navoni, Sandro Benigno, Chris Anderson, Randy McEvans
|
||||
|
||||
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:
|
||||
- 19-10-10 Initial CLI
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
- Full menu systems, debug, settings
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
|
||||
boolean ShowMainMenu;
|
||||
|
||||
|
||||
// CLI Functions
|
||||
// This can be moved later to CLI.pde
|
||||
void RunCLI () {
|
||||
|
||||
// APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
readUserConfig(); // Read memory values from EEPROM
|
||||
|
||||
ShowMainMenu = TRUE;
|
||||
// We need to initialize Serial again due it was not initialized during startup.
|
||||
SerBeg(SerBau);
|
||||
SerPrln();
|
||||
SerPrln("Welcome to ArduCopter CLI");
|
||||
SerPri("Firmware: ");
|
||||
SerPrln(VER);
|
||||
SerPrln();
|
||||
SerPrln("Make sure that you have Carriage Return active");
|
||||
|
||||
if(ShowMainMenu) Show_MainMenu();
|
||||
|
||||
// Our main loop that never ends. Only way to get away from here is to reboot APM
|
||||
for (;;) {
|
||||
|
||||
if(ShowMainMenu) Show_MainMenu();
|
||||
|
||||
delay(50);
|
||||
if (SerAva()) {
|
||||
ShowMainMenu = TRUE;
|
||||
queryType = SerRea();
|
||||
switch (queryType) {
|
||||
case 'a':
|
||||
Flip_MAG();
|
||||
break;
|
||||
case 'c':
|
||||
CALIB_CompassOffset();
|
||||
break;
|
||||
case 'd':
|
||||
Log_Read(1,4000);
|
||||
break;
|
||||
case 'i':
|
||||
CALIB_AccOffset();
|
||||
break;
|
||||
case 't':
|
||||
CALIB_Throttle();
|
||||
break;
|
||||
case 'e':
|
||||
CALIB_Esc();
|
||||
break;
|
||||
case 'o':
|
||||
Set_SonarAndObstacleAvoidance_PIDs();
|
||||
break;
|
||||
case 's':
|
||||
Show_Settings();
|
||||
break;
|
||||
case 'r':
|
||||
Reset_Settings();
|
||||
break;
|
||||
case 'm':
|
||||
RUN_Motors();
|
||||
break;
|
||||
case 'z':
|
||||
Log_Erase();
|
||||
break;
|
||||
}
|
||||
SerFlu();
|
||||
}
|
||||
|
||||
// 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();
|
||||
CLILedStep();
|
||||
}
|
||||
} // Mainloop ends
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void Show_MainMenu() {
|
||||
ShowMainMenu = FALSE;
|
||||
SerPrln();
|
||||
SerPrln("CLI Menu - Type your command on command prompt");
|
||||
SerPrln("----------------------------------------------");
|
||||
SerPrln(" a - Activate/Deactivate compass (check #IsMag define too)");
|
||||
SerPrln(" c - Show/Save compass offsets");
|
||||
SerPrln(" d - dump logs to serial");
|
||||
SerPrln(" e - ESC Throttle calibration (Works with official ArduCopter ESCs)");
|
||||
SerPrln(" i - Initialize and calibrate Accel offsets");
|
||||
SerPrln(" m - Motor tester with AIL/ELE stick");
|
||||
SerPrln(" o - Show/Save sonar & obstacle avoidance PIDs");
|
||||
SerPrln(" r - Reset to factory settings");
|
||||
SerPrln(" t - Calibrate MIN Throttle value");
|
||||
SerPrln(" s - Show settings");
|
||||
SerPrln(" z - clear all logs");
|
||||
SerPrln(" ");
|
||||
SerFlu();
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************** */
|
||||
// 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....");
|
||||
|
||||
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
|
||||
int counter = 0;
|
||||
|
||||
SerFlu();
|
||||
while(1) {
|
||||
static float min[3], max[3], offset[3];
|
||||
if((millis()- timer) > 100) {
|
||||
timer = millis();
|
||||
AP_Compass.read();
|
||||
AP_Compass.calculate(0,0); // roll = 0, pitch = 0 for this example
|
||||
|
||||
// capture min
|
||||
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;
|
||||
|
||||
// capture max
|
||||
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;
|
||||
|
||||
// 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:");
|
||||
SerPri(ToDeg(AP_Compass.heading));
|
||||
SerPri(" \t(");
|
||||
SerPri(AP_Compass.mag_x);
|
||||
SerPri(",");
|
||||
SerPri(AP_Compass.mag_y);
|
||||
SerPri(",");
|
||||
SerPri(AP_Compass.mag_z);
|
||||
SerPri(") ");
|
||||
|
||||
// display offsets
|
||||
SerPri("\t offsets(");
|
||||
SerPri(offset[0]);
|
||||
SerPri(",");
|
||||
SerPri(offset[1]);
|
||||
SerPri(",");
|
||||
SerPri(offset[2]);
|
||||
SerPri(")");
|
||||
SerPrln();
|
||||
|
||||
if(counter == 200) {
|
||||
counter = 0;
|
||||
SerPrln();
|
||||
SerPrln("Roll and Rotate your quad untill offsets are not changing!");
|
||||
// SerPrln("to exit from this loop, reboot your APM");
|
||||
SerPrln();
|
||||
delay(500);
|
||||
}
|
||||
counter++;
|
||||
}
|
||||
if(SerAva() > 0){
|
||||
|
||||
mag_offset_x = offset[0];
|
||||
mag_offset_y = offset[1];
|
||||
mag_offset_z = offset[2];
|
||||
|
||||
SerPrln("Saving Offsets to EEPROM");
|
||||
writeEEPROM(mag_offset_x, mag_offset_x_ADR);
|
||||
writeEEPROM(mag_offset_y, mag_offset_y_ADR);
|
||||
writeEEPROM(mag_offset_z, mag_offset_z_ADR);
|
||||
delay(500);
|
||||
SerPrln("Saved...");
|
||||
SerPrln();
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
#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
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************** */
|
||||
// Accell calibration
|
||||
void CALIB_AccOffset() {
|
||||
|
||||
int loopy;
|
||||
long xx = 0, xy = 0, xz = 0;
|
||||
|
||||
SerPrln("Initializing Accelerometers..");
|
||||
adc.Init(); // APM ADC library initialization
|
||||
// delay(250); // Giving small moment before starting
|
||||
|
||||
calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde)
|
||||
|
||||
SerPrln();
|
||||
SerPrln("Sampling 50 samples from Accelerometers, don't move your ArduCopter!");
|
||||
SerPrln("Sample:\tAcc-X\tAxx-Y\tAcc-Z");
|
||||
|
||||
for(loopy = 1; loopy <= 50; loopy++) {
|
||||
SerPri(" ");
|
||||
SerPri(loopy);
|
||||
SerPri(":");
|
||||
tab();
|
||||
SerPri(xx += adc.Ch(4));
|
||||
tab();
|
||||
SerPri(xy += adc.Ch(5));
|
||||
tab();
|
||||
SerPrln(xz += adc.Ch(6));
|
||||
delay(20);
|
||||
}
|
||||
|
||||
xx = xx / (loopy - 1);
|
||||
xy = xy / (loopy - 1);
|
||||
xz = xz / (loopy - 1);
|
||||
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: ");
|
||||
SerPri(" ");
|
||||
tab();
|
||||
SerPri(acc_offset_x);
|
||||
tab();
|
||||
SerPri(acc_offset_y);
|
||||
tab();
|
||||
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 ");
|
||||
SerPrln("those values, redo initialization or use Configurator for finetuning");
|
||||
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();
|
||||
}
|
||||
|
||||
|
||||
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");
|
||||
|
||||
}
|
||||
|
||||
|
||||
void CALIB_Throttle() {
|
||||
int tmpThrottle = 1200;
|
||||
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
SerPrln();
|
||||
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);
|
||||
APM_RC.OutputCh(3, 900);
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
|
||||
SerPrln("Motors: DISARMED");
|
||||
SerPrln();
|
||||
}
|
||||
|
||||
|
||||
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) {
|
||||
SerPrln("Left Motor");
|
||||
OutMotor(1);
|
||||
delay(500);
|
||||
}
|
||||
if(ch_roll > 1600) {
|
||||
SerPrln("Right Motor");
|
||||
OutMotor(0);
|
||||
delay(500);
|
||||
|
||||
}
|
||||
if(ch_pitch < 1400) {
|
||||
SerPrln("Front Motor");
|
||||
OutMotor(2);
|
||||
delay(500);
|
||||
|
||||
}
|
||||
if(ch_pitch > 1600) {
|
||||
SerPrln("Rear Motor");
|
||||
OutMotor(3);
|
||||
delay(500);
|
||||
|
||||
}
|
||||
|
||||
// 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();
|
||||
|
||||
delay(100);
|
||||
// delay(20);
|
||||
if(SerAva() > 0){
|
||||
SerFlu();
|
||||
SerPrln("Exiting motor/esc tester...");
|
||||
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();
|
||||
}
|
||||
|
||||
|
||||
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..");
|
||||
|
||||
}
|
||||
|
||||
|
||||
void Show_Settings() {
|
||||
// Reading current EEPROM values
|
||||
|
||||
SerPrln("ArduCopter - Current settings");
|
||||
SerPrln("-----------------------------");
|
||||
SerPri("Firmware: ");
|
||||
SerPri(VER);
|
||||
SerPrln();
|
||||
SerPrln();
|
||||
|
||||
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: ");
|
||||
SerPrln(MIN_THROTTLE);
|
||||
|
||||
SerPri("Magnetometer 1-ena/0-dis: ");
|
||||
SerPrln(MAGNETOMETER, DEC);
|
||||
|
||||
SerPri("Camera mode: ");
|
||||
SerPrln(cam_mode, DEC);
|
||||
|
||||
SerPri("Flight orientation: ");
|
||||
if(SW_DIP1) {
|
||||
SerPrln("x mode");
|
||||
}
|
||||
else {
|
||||
SerPrln("+ mode");
|
||||
}
|
||||
|
||||
Show_SonarAndObstacleAvoidance_PIDs();
|
||||
|
||||
SerPrln();
|
||||
}
|
||||
|
||||
// Display obstacle avoidance pids
|
||||
void Show_SonarAndObstacleAvoidance_PIDs() {
|
||||
SerPri("\tSonar PID: ");
|
||||
SerPri(KP_SONAR_ALTITUDE); cspc();
|
||||
SerPri(KI_SONAR_ALTITUDE); cspc();
|
||||
SerPrln(KD_SONAR_ALTITUDE);
|
||||
SerPri("\tObstacle SafetyZone: ");
|
||||
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);
|
||||
SerPrln();
|
||||
SerPri("\tMaxAngle: ");
|
||||
SerPri(RF_MAX_ANGLE);
|
||||
SerPrln();
|
||||
}
|
||||
|
||||
// save RF pids to eeprom
|
||||
void Save_SonarAndObstacleAvoidancePIDs_toEEPROM() {
|
||||
writeEEPROM(KP_RF_ROLL,KP_RF_ROLL_ADR);
|
||||
writeEEPROM(KI_RF_ROLL,KI_RF_ROLL_ADR);
|
||||
writeEEPROM(KD_RF_ROLL,KD_RF_ROLL_ADR);
|
||||
writeEEPROM(KP_RF_PITCH,KP_RF_PITCH_ADR);
|
||||
writeEEPROM(KI_RF_PITCH,KI_RF_PITCH_ADR);
|
||||
writeEEPROM(KD_RF_PITCH,KD_RF_PITCH_ADR);
|
||||
writeEEPROM(RF_MAX_ANGLE,RF_MAX_ANGLE_ADR);
|
||||
writeEEPROM(RF_SAFETY_ZONE,RF_SAFETY_ZONE_ADR);
|
||||
writeEEPROM(KP_SONAR_ALTITUDE,KP_SONAR_ALTITUDE_ADR);
|
||||
writeEEPROM(KI_SONAR_ALTITUDE,KI_SONAR_ALTITUDE_ADR);
|
||||
writeEEPROM(KD_SONAR_ALTITUDE,KD_SONAR_ALTITUDE_ADR);
|
||||
}
|
||||
|
||||
//
|
||||
void Set_SonarAndObstacleAvoidance_PIDs() {
|
||||
float tempVal1, tempVal2, tempVal3;
|
||||
int saveToEeprom = 0;
|
||||
// Display current PID values
|
||||
SerPrln("Sonar and Obstacle Avoidance:");
|
||||
Show_SonarAndObstacleAvoidance_PIDs();
|
||||
SerPrln();
|
||||
|
||||
// SONAR PIDs
|
||||
SerFlu();
|
||||
SerPri("Enter Sonar 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_SONAR_ALTITUDE = tempVal1;
|
||||
KI_SONAR_ALTITUDE = tempVal2;
|
||||
KD_SONAR_ALTITUDE = tempVal3;
|
||||
SerPrln();
|
||||
SerPri("P:");
|
||||
SerPri(KP_SONAR_ALTITUDE);
|
||||
SerPri("\tI:");
|
||||
SerPri(KI_SONAR_ALTITUDE);
|
||||
SerPri("\tD:");
|
||||
SerPri(KD_SONAR_ALTITUDE);
|
||||
saveToEeprom = 1;
|
||||
}
|
||||
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 <= 700 ) {
|
||||
RF_SAFETY_ZONE = tempVal1;
|
||||
SerPri("SafetyZone: ");
|
||||
SerPri(RF_SAFETY_ZONE);
|
||||
saveToEeprom = 1;
|
||||
}
|
||||
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 && tempVal1 < 90 ) {
|
||||
RF_MAX_ANGLE = tempVal1;
|
||||
SerPrln();
|
||||
SerPri("MaxAngle: ");
|
||||
SerPri(RF_MAX_ANGLE);
|
||||
saveToEeprom = 1;
|
||||
}
|
||||
SerPrln();
|
||||
|
||||
// save to eeprom
|
||||
if( saveToEeprom == 1 ) {
|
||||
SerPrln("Obstacle Avoidance:");
|
||||
Show_SonarAndObstacleAvoidance_PIDs();
|
||||
SerPrln();
|
||||
Save_SonarAndObstacleAvoidancePIDs_toEEPROM();
|
||||
SerPrln("Saved to EEPROM");
|
||||
SerPrln();
|
||||
}else{
|
||||
SerPrln("No changes. Nothing saved to EEPROM");
|
||||
SerPrln();
|
||||
}
|
||||
}
|
||||
|
||||
void cspc() {
|
||||
SerPri(", ");
|
||||
}
|
||||
|
||||
void WaitSerialEnter() {
|
||||
// Flush serials
|
||||
SerFlu();
|
||||
delay(50);
|
||||
while(1) {
|
||||
if(SerAva() > 0){
|
||||
break;
|
||||
}
|
||||
delay(20);
|
||||
}
|
||||
delay(250);
|
||||
SerFlu();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -1,238 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : DCM.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
/* ******************************************* */
|
||||
|
||||
/* ******* DCM IMU functions ********************* */
|
||||
/**************************************************/
|
||||
void Normalize(void)
|
||||
{
|
||||
float error=0;
|
||||
float temporary[3][3];
|
||||
float renorm=0;
|
||||
|
||||
error= -Vector_Dot_Product(&DCM_Matrix[0][0],&DCM_Matrix[1][0])*.5; //eq.19
|
||||
|
||||
Vector_Scale(&temporary[0][0], &DCM_Matrix[1][0], error); //eq.19
|
||||
Vector_Scale(&temporary[1][0], &DCM_Matrix[0][0], error); //eq.19
|
||||
|
||||
Vector_Add(&temporary[0][0], &temporary[0][0], &DCM_Matrix[0][0]);//eq.19
|
||||
Vector_Add(&temporary[1][0], &temporary[1][0], &DCM_Matrix[1][0]);//eq.19
|
||||
|
||||
Vector_Cross_Product(&temporary[2][0],&temporary[0][0],&temporary[1][0]); // c= a x b //eq.20
|
||||
|
||||
renorm= .5 *(3 - Vector_Dot_Product(&temporary[0][0],&temporary[0][0])); //eq.21
|
||||
Vector_Scale(&DCM_Matrix[0][0], &temporary[0][0], renorm);
|
||||
|
||||
renorm= .5 *(3 - Vector_Dot_Product(&temporary[1][0],&temporary[1][0])); //eq.21
|
||||
Vector_Scale(&DCM_Matrix[1][0], &temporary[1][0], renorm);
|
||||
|
||||
renorm= .5 *(3 - Vector_Dot_Product(&temporary[2][0],&temporary[2][0])); //eq.21
|
||||
Vector_Scale(&DCM_Matrix[2][0], &temporary[2][0], renorm);
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
void Drift_correction(void)
|
||||
{
|
||||
//Compensation the Roll, Pitch and Yaw drift.
|
||||
float errorCourse;
|
||||
static float Scaled_Omega_P[3];
|
||||
static float Scaled_Omega_I[3];
|
||||
|
||||
//*****Roll and Pitch***************
|
||||
|
||||
Vector_Cross_Product(&errorRollPitch[0],&Accel_Vector[0],&DCM_Matrix[2][0]); //adjust the ground of reference
|
||||
// errorRollPitch are in Accel ADC units
|
||||
// Limit max errorRollPitch to limit max Omega_P and Omega_I
|
||||
errorRollPitch[0] = constrain(errorRollPitch[0],-50,50);
|
||||
errorRollPitch[1] = constrain(errorRollPitch[1],-50,50);
|
||||
errorRollPitch[2] = constrain(errorRollPitch[2],-50,50);
|
||||
Vector_Scale(&Omega_P[0],&errorRollPitch[0],Kp_ROLLPITCH);
|
||||
|
||||
Vector_Scale(&Scaled_Omega_I[0],&errorRollPitch[0],Ki_ROLLPITCH);
|
||||
Vector_Add(Omega_I,Omega_I,Scaled_Omega_I);
|
||||
|
||||
//*****YAW***************
|
||||
// We make the gyro YAW drift correction based on compass magnetic heading
|
||||
if (MAGNETOMETER == 1) {
|
||||
errorCourse= (DCM_Matrix[0][0]*AP_Compass.heading_y) - (DCM_Matrix[1][0]*AP_Compass.heading_x); //Calculating YAW error
|
||||
Vector_Scale(errorYaw,&DCM_Matrix[2][0],errorCourse); //Applys the yaw correction to the XYZ rotation of the aircraft, depeding the position.
|
||||
|
||||
Vector_Scale(&Scaled_Omega_P[0],&errorYaw[0],Kp_YAW);
|
||||
Vector_Add(Omega_P,Omega_P,Scaled_Omega_P);//Adding Proportional.
|
||||
|
||||
// Limit max errorYaw to limit max Omega_I
|
||||
errorYaw[0] = constrain(errorYaw[0],-50,50);
|
||||
errorYaw[1] = constrain(errorYaw[1],-50,50);
|
||||
errorYaw[2] = constrain(errorYaw[2],-50,50);
|
||||
|
||||
Vector_Scale(&Scaled_Omega_I[0],&errorYaw[0],Ki_YAW);
|
||||
Vector_Add(Omega_I,Omega_I,Scaled_Omega_I);//adding integrator to the Omega_I
|
||||
}
|
||||
|
||||
}
|
||||
/**************************************************/
|
||||
void Accel_adjust(void)
|
||||
{
|
||||
//Accel_Vector[1] += Accel_Scale(speed_3d*Omega[2]); // Centrifugal force on Acc_y = GPS_speed*GyroZ
|
||||
//Accel_Vector[2] -= Accel_Scale(speed_3d*Omega[1]); // Centrifugal force on Acc_z = GPS_speed*GyroY
|
||||
}
|
||||
/**************************************************/
|
||||
|
||||
void Matrix_update(void)
|
||||
{
|
||||
Gyro_Vector[0]=Gyro_Scaled_X(read_adc(0)); //gyro x roll
|
||||
Gyro_Vector[1]=Gyro_Scaled_Y(read_adc(1)); //gyro y pitch
|
||||
Gyro_Vector[2]=Gyro_Scaled_Z(read_adc(2)); //gyro Z yaw
|
||||
|
||||
// Low pass filter on accelerometer data (to filter vibrations)
|
||||
Accel_Vector[0]=Accel_Vector[0]*0.6 + (float)read_adc(3)*0.4; // acc x
|
||||
Accel_Vector[1]=Accel_Vector[1]*0.6 + (float)read_adc(4)*0.4; // acc y
|
||||
Accel_Vector[2]=Accel_Vector[2]*0.6 + (float)read_adc(5)*0.4; // acc z
|
||||
|
||||
Vector_Add(&Omega[0], &Gyro_Vector[0], &Omega_I[0]);//adding integrator
|
||||
Vector_Add(&Omega_Vector[0], &Omega[0], &Omega_P[0]);//adding proportional
|
||||
|
||||
//Accel_adjust();//adjusting centrifugal acceleration. // Not used for quadcopter
|
||||
|
||||
#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
|
||||
Update_Matrix[1][0]=G_Dt*Omega_Vector[2];//z
|
||||
Update_Matrix[1][1]=0;
|
||||
Update_Matrix[1][2]=-G_Dt*Omega_Vector[0];//-x
|
||||
Update_Matrix[2][0]=-G_Dt*Omega_Vector[1];//-y
|
||||
Update_Matrix[2][1]=G_Dt*Omega_Vector[0];//x
|
||||
Update_Matrix[2][2]=0;
|
||||
#endif
|
||||
#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
|
||||
Update_Matrix[1][0]=G_Dt*Gyro_Vector[2];//z
|
||||
Update_Matrix[1][1]=0;
|
||||
Update_Matrix[1][2]=-G_Dt*Gyro_Vector[0];
|
||||
Update_Matrix[2][0]=-G_Dt*Gyro_Vector[1];
|
||||
Update_Matrix[2][1]=G_Dt*Gyro_Vector[0];
|
||||
Update_Matrix[2][2]=0;
|
||||
#endif
|
||||
|
||||
Matrix_Multiply(DCM_Matrix,Update_Matrix,Temporary_Matrix); //a*b=c
|
||||
|
||||
for(int x=0; x<3; x++) //Matrix Addition (update)
|
||||
{
|
||||
for(int y=0; y<3; y++)
|
||||
{
|
||||
DCM_Matrix[x][y]+=Temporary_Matrix[x][y];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Euler_angles(void)
|
||||
{
|
||||
#if (OUTPUTMODE==2) // Only accelerometer info (debugging purposes)
|
||||
roll = atan2(Accel_Vector[1],Accel_Vector[2]); // atan2(acc_y,acc_z)
|
||||
pitch = -asin((Accel_Vector[0])/(float)GRAVITY); // asin(acc_x)
|
||||
yaw = 0;
|
||||
#else // Euler angles from DCM matrix
|
||||
pitch = asin(-DCM_Matrix[2][0]);
|
||||
roll = atan2(DCM_Matrix[2][1],DCM_Matrix[2][2]);
|
||||
yaw = atan2(DCM_Matrix[1][0],DCM_Matrix[0][0]);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// VECTOR FUNCTIONS
|
||||
//Computes the dot product of two vectors
|
||||
float Vector_Dot_Product(float vector1[3],float vector2[3])
|
||||
{
|
||||
float op=0;
|
||||
|
||||
for(int c=0; c<3; c++)
|
||||
{
|
||||
op+=vector1[c]*vector2[c];
|
||||
}
|
||||
|
||||
return op;
|
||||
}
|
||||
|
||||
//Computes the cross product of two vectors
|
||||
void Vector_Cross_Product(float vectorOut[3], float v1[3],float v2[3])
|
||||
{
|
||||
vectorOut[0]= (v1[1]*v2[2]) - (v1[2]*v2[1]);
|
||||
vectorOut[1]= (v1[2]*v2[0]) - (v1[0]*v2[2]);
|
||||
vectorOut[2]= (v1[0]*v2[1]) - (v1[1]*v2[0]);
|
||||
}
|
||||
|
||||
//Multiply the vector by a scalar.
|
||||
void Vector_Scale(float vectorOut[3],float vectorIn[3], float scale2)
|
||||
{
|
||||
for(int c=0; c<3; c++)
|
||||
{
|
||||
vectorOut[c]=vectorIn[c]*scale2;
|
||||
}
|
||||
}
|
||||
|
||||
void Vector_Add(float vectorOut[3],float vectorIn1[3], float vectorIn2[3])
|
||||
{
|
||||
for(int c=0; c<3; c++)
|
||||
{
|
||||
vectorOut[c]=vectorIn1[c]+vectorIn2[c];
|
||||
}
|
||||
}
|
||||
|
||||
/********* MATRIX FUNCTIONS *****************************************/
|
||||
//Multiply two 3x3 matrixs. This function developed by Jordi can be easily adapted to multiple n*n matrix's. (Pero me da flojera!).
|
||||
void Matrix_Multiply(float a[3][3], float b[3][3],float mat[3][3])
|
||||
{
|
||||
float op[3];
|
||||
for(int x=0; x<3; x++)
|
||||
{
|
||||
for(int y=0; y<3; y++)
|
||||
{
|
||||
for(int w=0; w<3; w++)
|
||||
{
|
||||
op[w]=a[x][w]*b[w][y];
|
||||
}
|
||||
mat[x][y]=0;
|
||||
mat[x][y]=op[0]+op[1]+op[2];
|
||||
|
||||
float test=mat[x][y];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,546 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Debug.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 1
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Radio Subsystem ");
|
||||
while(1){
|
||||
delay(20);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
Serial.print("Radio in ch1: ");
|
||||
Serial.print(radio_in[CH_ROLL], DEC);
|
||||
Serial.print("\tch2: ");
|
||||
Serial.print(radio_in[CH_PITCH], DEC);
|
||||
Serial.print("\tch3: ");
|
||||
Serial.print(radio_in[CH_THROTTLE], DEC);
|
||||
Serial.print("\tch4: ");
|
||||
Serial.print(radio_in[CH_RUDDER], DEC);
|
||||
Serial.print("\tch5: ");
|
||||
Serial.print(radio_in[4], DEC);
|
||||
Serial.print("\tch6: ");
|
||||
Serial.print(radio_in[5], DEC);
|
||||
Serial.print("\tch7: ");
|
||||
Serial.print(radio_in[6], DEC);
|
||||
Serial.print("\tch8: ");
|
||||
Serial.println(radio_in[7], DEC);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 2
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Servo Subsystem ");
|
||||
Serial.print("Reverse ROLL - CH1: ");
|
||||
Serial.println(reverse_roll, DEC);
|
||||
Serial.print("Reverse PITCH - CH2: ");
|
||||
Serial.println(reverse_pitch, DEC);
|
||||
Serial.print("Reverse THROTTLE - CH3: ");
|
||||
Serial.println(REVERSE_THROTTLE, DEC);
|
||||
Serial.print("Reverse RUDDER - CH4: ");
|
||||
Serial.println(reverse_rudder, DEC);
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
trim_radio();
|
||||
|
||||
radio_max[0] = CH1_MAX;
|
||||
radio_max[1] = CH2_MAX;
|
||||
radio_max[2] = CH3_MAX;
|
||||
radio_max[3] = CH4_MAX;
|
||||
radio_max[4] = CH5_MAX;
|
||||
radio_max[5] = CH6_MAX;
|
||||
radio_max[6] = CH7_MAX;
|
||||
radio_max[7] = CH8_MAX;
|
||||
radio_min[0] = CH1_MIN;
|
||||
radio_min[1] = CH2_MIN;
|
||||
radio_min[2] = CH3_MIN;
|
||||
radio_min[3] = CH4_MIN;
|
||||
radio_min[4] = CH5_MIN;
|
||||
radio_min[5] = CH6_MIN;
|
||||
radio_min[6] = CH7_MIN;
|
||||
radio_min[7] = CH8_MIN;
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
update_servo_switches();
|
||||
|
||||
servo_out[CH_ROLL] = ((radio_in[CH_ROLL] - radio_trim[CH_ROLL]) * 45.0f * reverse_roll) / 500;
|
||||
servo_out[CH_PITCH] = ((radio_in[CH_PITCH] - radio_trim[CH_PITCH]) * 45.0f * reverse_roll) / 500;
|
||||
servo_out[CH_RUDDER] = ((radio_in[CH_RUDDER] - radio_trim[CH_RUDDER]) * 45.0f * reverse_rudder) / 500;
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
|
||||
|
||||
for(int y = 4; y < 8; y++) {
|
||||
radio_out[y] = constrain(radio_in[y], radio_min[y], radio_max[y]);
|
||||
APM_RC.OutputCh(y, radio_out[y]); // send to Servos
|
||||
}
|
||||
|
||||
/*
|
||||
Serial.print("Servo_out ch1: ");
|
||||
Serial.print(servo_out[CH_ROLL], DEC);
|
||||
Serial.print("\tch2: ");
|
||||
Serial.print(servo_out[CH_PITCH], DEC);
|
||||
Serial.print("\tch3: ");
|
||||
Serial.print(servo_out[CH_THROTTLE], DEC);
|
||||
Serial.print("\tch4: ");
|
||||
Serial.print(servo_out[CH_RUDDER], DEC);
|
||||
*/
|
||||
///*
|
||||
Serial.print("ch1: ");
|
||||
Serial.print(radio_out[CH_ROLL], DEC);
|
||||
Serial.print("\tch2: ");
|
||||
Serial.print(radio_out[CH_PITCH], DEC);
|
||||
Serial.print("\tch3: ");
|
||||
Serial.print(radio_out[CH_THROTTLE], DEC);
|
||||
Serial.print("\tch4: ");
|
||||
Serial.print(radio_out[CH_RUDDER], DEC);
|
||||
Serial.print("\tch5: ");
|
||||
Serial.print(radio_out[4], DEC);
|
||||
Serial.print("\tch6: ");
|
||||
Serial.print(radio_out[5], DEC);
|
||||
Serial.print("\tch7: ");
|
||||
Serial.print(radio_out[6], DEC);
|
||||
Serial.print("\tch8: ");
|
||||
Serial.println(radio_out[7], DEC);
|
||||
|
||||
//*/
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 3
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Analog Sensor Subsystem ");
|
||||
|
||||
Serial.print("AirSpeed sensor enabled: ");
|
||||
Serial.println(AIRSPEED_SENSOR, DEC);
|
||||
|
||||
Serial.print("Enable Battery: ");
|
||||
Serial.println(BATTERY_EVENT, DEC);
|
||||
zero_airspeed();
|
||||
|
||||
Serial.print("Air pressure offset:");
|
||||
Serial.println(airpressure_offset, DEC);
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
read_z_sensor();
|
||||
read_XY_sensors();
|
||||
read_battery();
|
||||
|
||||
Serial.print("Analog IN:");
|
||||
Serial.print(" 0:");
|
||||
Serial.print(analog0, DEC);
|
||||
Serial.print(", 1: ");
|
||||
Serial.print(analog1, DEC);
|
||||
Serial.print(", 2: ");
|
||||
Serial.print(analog2, DEC);
|
||||
Serial.print(", 3: ");
|
||||
Serial.print(airpressure_raw, DEC);
|
||||
|
||||
Serial.print("\t\tSensors:");
|
||||
Serial.print(" airSpeed:");
|
||||
Serial.print(airspeed, DEC);
|
||||
Serial.print("m \tbattV:");
|
||||
Serial.print(battery_voltage, DEC);
|
||||
Serial.println("volts ");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 4
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: GPS Subsystem ");
|
||||
|
||||
while(1){
|
||||
delay(333);
|
||||
|
||||
// Blink GPS LED if we don't have a fix
|
||||
// ------------------------------------
|
||||
//update_GPS_light();
|
||||
|
||||
GPS.Read();
|
||||
|
||||
if (GPS.NewData){
|
||||
Serial.print("Lat:");
|
||||
Serial.print(GPS.Lattitude, DEC);
|
||||
Serial.print(" Lon:");
|
||||
Serial.print(GPS.Longitude, DEC);
|
||||
Serial.print(" Alt:");
|
||||
Serial.print(GPS.Altitude / 100, DEC);
|
||||
Serial.print("m, gs: ");
|
||||
Serial.print(GPS.Ground_Speed / 100, DEC);
|
||||
Serial.print(" COG:");
|
||||
Serial.print(GPS.Ground_Course / 1000l);
|
||||
Serial.print(" SAT:");
|
||||
Serial.print(GPS.NumSats, DEC);
|
||||
Serial.print(" FIX:");
|
||||
Serial.print(GPS.Fix, DEC);
|
||||
Serial.print(" TIM:");
|
||||
Serial.print(GPS.Time);
|
||||
Serial.println();
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 5
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: GPS Subsystem, RAW OUTPUT");
|
||||
|
||||
while(1){
|
||||
if(Serial1.available() > 0) // Ok, let me see, the buffer is empty?
|
||||
{
|
||||
|
||||
delay(60); // wait for it all
|
||||
while(Serial1.available() > 0){
|
||||
byte incoming = Serial1.read();
|
||||
//Serial.print(incoming,DEC);
|
||||
Serial.print(incoming, HEX); // will output Hex values
|
||||
Serial.print(",");
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 6
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: IMU Subsystem ");
|
||||
startup_IMU_ground();
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
read_AHRS();
|
||||
|
||||
// We are using the IMU
|
||||
// ---------------------
|
||||
Serial.print(" roll:");
|
||||
Serial.print(roll_sensor / 100, DEC);
|
||||
Serial.print(" pitch:");
|
||||
Serial.print(pitch_sensor / 100, DEC);
|
||||
Serial.print(" yaw:");
|
||||
Serial.println(yaw_sensor / 100, DEC);
|
||||
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 7
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Control Switch Test");
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
byte switchPosition = readSwitch();
|
||||
if (oldSwitchPosition != switchPosition){
|
||||
|
||||
switch(switchPosition)
|
||||
{
|
||||
case 1: // First position
|
||||
Serial.println("Position 1");
|
||||
|
||||
break;
|
||||
|
||||
case 2: // middle position
|
||||
Serial.println("Position 2");
|
||||
break;
|
||||
|
||||
case 3: // last position
|
||||
Serial.println("Position 3");
|
||||
break;
|
||||
|
||||
case 4: // last position
|
||||
Serial.println("Position 4");
|
||||
break;
|
||||
|
||||
case 5: // last position
|
||||
Serial.println("Position 5 - Software Manual");
|
||||
break;
|
||||
|
||||
case 6: // last position
|
||||
Serial.println("Position 6 - Hardware MUX, Manual");
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 8
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Control Switch Test");
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
update_servo_switches();
|
||||
if (mix_mode == 0) {
|
||||
Serial.print("Mix:standard ");
|
||||
Serial.print("\t reverse_roll: ");
|
||||
Serial.print(reverse_roll, DEC);
|
||||
Serial.print("\t reverse_pitch: ");
|
||||
Serial.print(reverse_pitch, DEC);
|
||||
Serial.print("\t reverse_rudder: ");
|
||||
Serial.println(reverse_rudder, DEC);
|
||||
} else {
|
||||
Serial.print("Mix:elevons ");
|
||||
Serial.print("\t reverse_elevons: ");
|
||||
Serial.print(reverse_elevons, DEC);
|
||||
Serial.print("\t reverse_ch1_elevon: ");
|
||||
Serial.print(reverse_ch1_elevon, DEC);
|
||||
Serial.print("\t reverse_ch2_elevon: ");
|
||||
Serial.println(reverse_ch2_elevon, DEC);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 9
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Relay");
|
||||
pinMode(RELAY_PIN, OUTPUT);
|
||||
|
||||
while(1){
|
||||
delay(3000);
|
||||
|
||||
Serial.println("Relay Position A");
|
||||
PORTL |= B00000100;
|
||||
delay(3000);
|
||||
|
||||
Serial.println("Relay Position B");
|
||||
PORTL ^= B00000100;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 10
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Magnatometer");
|
||||
|
||||
while(1){
|
||||
delay(3000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 11
|
||||
void debug_subsystem()
|
||||
{
|
||||
ground_alt = 0;
|
||||
Serial.println("Begin Debug: Absolute Airpressure");
|
||||
while(1){
|
||||
delay(20);
|
||||
read_airpressure();
|
||||
Serial.print("Air Pressure Altitude: ");
|
||||
Serial.print(press_alt / 100, DEC);
|
||||
Serial.println("meters");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 12
|
||||
void debug_subsystem()
|
||||
{
|
||||
ground_alt = 0;
|
||||
Serial.println("Begin Debug: Display Waypoints");
|
||||
delay(500);
|
||||
|
||||
eeprom_busy_wait();
|
||||
uint8_t options = eeprom_read_byte((uint8_t *) EE_CONFIG);
|
||||
|
||||
eeprom_busy_wait();
|
||||
int32_t hold = eeprom_read_dword((uint32_t *) EE_ALT_HOLD_HOME);
|
||||
|
||||
// save the alitude above home option
|
||||
if(options & HOLD_ALT_ABOVE_HOME){
|
||||
Serial.print("Hold this altitude over home: ");
|
||||
Serial.print(hold / 100, DEC);
|
||||
Serial.println(" meters");
|
||||
}else{
|
||||
Serial.println("Maintain current altitude ");
|
||||
}
|
||||
|
||||
Serial.print("Number of Waypoints: ");
|
||||
Serial.println(wp_total, DEC);
|
||||
|
||||
Serial.print("Hit radius for Waypoints: ");
|
||||
Serial.println(wp_radius, DEC);
|
||||
|
||||
Serial.print("Loiter radius around Waypoints: ");
|
||||
Serial.println(loiter_radius, DEC);
|
||||
Serial.println(" ");
|
||||
|
||||
for(byte i = 0; i < wp_total; i++){
|
||||
struct Location temp = get_wp_with_index(i);
|
||||
print_waypoint(&temp, i);
|
||||
}
|
||||
|
||||
while(1){
|
||||
}
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 13
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Throttle Subsystem ");
|
||||
read_radio();
|
||||
|
||||
uint16_t low_pwm = radio_in[CH_THROTTLE];
|
||||
uint16_t high_pwm = radio_in[CH_THROTTLE];
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
//update_throttle();
|
||||
set_servos_4();
|
||||
low_pwm = min(low_pwm, radio_in[CH_THROTTLE]);
|
||||
high_pwm = max(high_pwm, radio_in[CH_THROTTLE]);
|
||||
|
||||
Serial.print("Radio_in: ");
|
||||
Serial.print(radio_in[CH_THROTTLE], DEC);
|
||||
Serial.print("\tPWM output: ");
|
||||
Serial.print(radio_out[CH_THROTTLE], DEC);
|
||||
Serial.print("\tThrottle: ");
|
||||
Serial.print(servo_out[CH_THROTTLE], DEC);
|
||||
Serial.print("\tPWM Min: ");
|
||||
Serial.print(low_pwm, DEC);
|
||||
Serial.print("\tPWM Max: ");
|
||||
Serial.println(high_pwm, DEC);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 14
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: Radio Min Max ");
|
||||
uint16_t low_pwm[8];
|
||||
uint16_t high_pwm[8];
|
||||
uint8_t i;
|
||||
|
||||
for(i = 0; i < 100; i++){
|
||||
delay(20);
|
||||
read_radio();
|
||||
}
|
||||
|
||||
for(i = 0; i < 8; i++){
|
||||
radio_min[i] = 0;
|
||||
radio_max[i] = 2400;
|
||||
low_pwm[i] = radio_in[i];
|
||||
high_pwm[i] = radio_in[i];
|
||||
}
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
for(i = 0; i < 8; i++){
|
||||
low_pwm[i] = min(low_pwm[i], radio_in[i]);
|
||||
high_pwm[i] = max(high_pwm[i], radio_in[i]);
|
||||
}
|
||||
|
||||
for(i = 0; i < 8; i++){
|
||||
Serial.print("CH");
|
||||
Serial.print(i + 1, DEC);
|
||||
Serial.print(": ");
|
||||
low_pwm[i] = min(low_pwm[i], radio_in[i]);
|
||||
Serial.print(low_pwm[i], DEC);
|
||||
Serial.print("|");
|
||||
high_pwm[i] = max(high_pwm[i], radio_in[i]);
|
||||
Serial.print(high_pwm[i], DEC);
|
||||
Serial.print(" ");
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#if DEBUG_SUBSYSTEM == 15
|
||||
void debug_subsystem()
|
||||
{
|
||||
Serial.println("Begin Debug: EEPROM Dump ");
|
||||
uint16_t temp;
|
||||
for(int n = 0; n < 512; n++){
|
||||
for(int i = 0; i < 4; i++){
|
||||
temp = eeprom_read_word((uint16_t *) mem);
|
||||
mem += 2;
|
||||
Serial.print(temp, HEX);
|
||||
Serial.print(" ");
|
||||
}
|
||||
Serial.print(" ");
|
||||
for(int i = 0; i < 4; i++){
|
||||
temp = eeprom_read_word((uint16_t *) mem);
|
||||
mem += 2;
|
||||
Serial.print(temp, HEX);
|
||||
Serial.print(" ");
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
@ -1,219 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : EEPROM.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
// Utilities for writing and reading from the EEPROM
|
||||
float readEEPROM(int address) {
|
||||
union floatStore {
|
||||
byte floatByte[4];
|
||||
float floatVal;
|
||||
} floatOut;
|
||||
|
||||
for (int i = 0; i < 4; i++)
|
||||
floatOut.floatByte[i] = EEPROM.read(address + i);
|
||||
return floatOut.floatVal;
|
||||
}
|
||||
|
||||
void writeEEPROM(float value, int address) {
|
||||
union floatStore {
|
||||
byte floatByte[4];
|
||||
float floatVal;
|
||||
} floatIn;
|
||||
|
||||
floatIn.floatVal = value;
|
||||
for (int i = 0; i < 4; i++)
|
||||
EEPROM.write(address + i, floatIn.floatByte[i]);
|
||||
}
|
||||
|
||||
void readUserConfig() {
|
||||
// eeprom_counter = readEEPROM(eeprom_counter_ADR);
|
||||
// eeprom_checker = readEEPROM(eeprom_checker_ADR);
|
||||
KP_QUAD_ROLL = readEEPROM(KP_QUAD_ROLL_ADR);
|
||||
KI_QUAD_ROLL = readEEPROM(KI_QUAD_ROLL_ADR);
|
||||
STABLE_MODE_KP_RATE_ROLL = readEEPROM(STABLE_MODE_KP_RATE_ROLL_ADR);
|
||||
KP_QUAD_PITCH = readEEPROM(KP_QUAD_PITCH_ADR);
|
||||
KI_QUAD_PITCH = readEEPROM(KI_QUAD_PITCH_ADR);
|
||||
STABLE_MODE_KP_RATE_PITCH = readEEPROM(STABLE_MODE_KP_RATE_PITCH_ADR);
|
||||
KP_QUAD_YAW = readEEPROM(KP_QUAD_YAW_ADR);
|
||||
KI_QUAD_YAW = readEEPROM(KI_QUAD_YAW_ADR);
|
||||
STABLE_MODE_KP_RATE_YAW = readEEPROM(STABLE_MODE_KP_RATE_YAW_ADR);
|
||||
STABLE_MODE_KP_RATE = readEEPROM(STABLE_MODE_KP_RATE_ADR); // NOT USED NOW
|
||||
KP_GPS_ROLL = readEEPROM(KP_GPS_ROLL_ADR);
|
||||
KI_GPS_ROLL = readEEPROM(KI_GPS_ROLL_ADR);
|
||||
KD_GPS_ROLL = readEEPROM(KD_GPS_ROLL_ADR);
|
||||
KP_GPS_PITCH = readEEPROM(KP_GPS_PITCH_ADR);
|
||||
KI_GPS_PITCH = readEEPROM(KI_GPS_PITCH_ADR);
|
||||
KD_GPS_PITCH = readEEPROM(KD_GPS_PITCH_ADR);
|
||||
GPS_MAX_ANGLE = readEEPROM(GPS_MAX_ANGLE_ADR);
|
||||
KP_ALTITUDE = readEEPROM(KP_ALTITUDE_ADR);
|
||||
KI_ALTITUDE = readEEPROM(KI_ALTITUDE_ADR);
|
||||
KD_ALTITUDE = readEEPROM(KD_ALTITUDE_ADR);
|
||||
acc_offset_x = readEEPROM(acc_offset_x_ADR);
|
||||
acc_offset_y = readEEPROM(acc_offset_y_ADR);
|
||||
acc_offset_z = readEEPROM(acc_offset_z_ADR);
|
||||
gyro_offset_roll = readEEPROM(gyro_offset_roll_ADR);
|
||||
gyro_offset_pitch = readEEPROM(gyro_offset_pitch_ADR);
|
||||
gyro_offset_yaw = readEEPROM(gyro_offset_yaw_ADR);
|
||||
Kp_ROLLPITCH = readEEPROM(Kp_ROLLPITCH_ADR);
|
||||
Ki_ROLLPITCH = readEEPROM(Ki_ROLLPITCH_ADR);
|
||||
Kp_YAW = readEEPROM(Kp_YAW_ADR);
|
||||
Ki_YAW = readEEPROM(Ki_YAW_ADR);
|
||||
GEOG_CORRECTION_FACTOR = readEEPROM(GEOG_CORRECTION_FACTOR_ADR);
|
||||
MAGNETOMETER = readEEPROM(MAGNETOMETER_ADR);
|
||||
Kp_RateRoll = readEEPROM(KP_RATEROLL_ADR);
|
||||
Ki_RateRoll = readEEPROM(KI_RATEROLL_ADR);
|
||||
Kd_RateRoll = readEEPROM(KD_RATEROLL_ADR);
|
||||
Kp_RatePitch = readEEPROM(KP_RATEPITCH_ADR);
|
||||
Ki_RatePitch = readEEPROM(KI_RATEPITCH_ADR);
|
||||
Kd_RatePitch = readEEPROM(KD_RATEPITCH_ADR);
|
||||
Kp_RateYaw = readEEPROM(KP_RATEYAW_ADR);
|
||||
Ki_RateYaw = readEEPROM(KI_RATEYAW_ADR);
|
||||
Kd_RateYaw = readEEPROM(KD_RATEYAW_ADR);
|
||||
xmitFactor = readEEPROM(XMITFACTOR_ADR);
|
||||
roll_mid = readEEPROM(CHROLL_MID);
|
||||
pitch_mid = readEEPROM(CHPITCH_MID);
|
||||
yaw_mid = readEEPROM(CHYAW_MID);
|
||||
ch_roll_slope = readEEPROM(ch_roll_slope_ADR);
|
||||
ch_pitch_slope = readEEPROM(ch_pitch_slope_ADR);
|
||||
ch_throttle_slope = readEEPROM(ch_throttle_slope_ADR);
|
||||
ch_yaw_slope = readEEPROM(ch_yaw_slope_ADR);
|
||||
ch_aux_slope = readEEPROM(ch_aux_slope_ADR);
|
||||
ch_aux2_slope = readEEPROM(ch_aux2_slope_ADR);
|
||||
ch_roll_offset = readEEPROM(ch_roll_offset_ADR);
|
||||
ch_pitch_offset = readEEPROM(ch_pitch_offset_ADR);
|
||||
ch_throttle_offset = readEEPROM(ch_throttle_offset_ADR);
|
||||
ch_yaw_offset = readEEPROM(ch_yaw_offset_ADR);
|
||||
ch_aux_offset = readEEPROM(ch_aux_offset_ADR);
|
||||
ch_aux2_offset = readEEPROM(ch_aux2_offset_ADR);
|
||||
cam_mode = readEEPROM(cam_mode_ADR);
|
||||
mag_orientation = readEEPROM(mag_orientation_ADR);
|
||||
mag_declination = readEEPROM(mag_declination_ADR);
|
||||
mag_offset_x = readEEPROM(mag_offset_x_ADR);
|
||||
mag_offset_y = readEEPROM(mag_offset_y_ADR);
|
||||
mag_offset_z = readEEPROM(mag_offset_z_ADR);
|
||||
MIN_THROTTLE = readEEPROM(MIN_THROTTLE_ADR);
|
||||
KP_RF_ROLL = readEEPROM(KP_RF_ROLL_ADR);
|
||||
KD_RF_ROLL = readEEPROM(KD_RF_ROLL_ADR);
|
||||
KI_RF_ROLL = readEEPROM(KI_RF_ROLL_ADR);
|
||||
KP_RF_PITCH = readEEPROM(KP_RF_PITCH_ADR);
|
||||
KD_RF_PITCH = readEEPROM(KD_RF_PITCH_ADR);
|
||||
KI_RF_PITCH = readEEPROM(KI_RF_PITCH_ADR);
|
||||
RF_MAX_ANGLE = readEEPROM(RF_MAX_ANGLE_ADR);
|
||||
RF_SAFETY_ZONE = readEEPROM(RF_SAFETY_ZONE_ADR);
|
||||
KP_SONAR_ALTITUDE = readEEPROM(KP_SONAR_ALTITUDE_ADR);
|
||||
KI_SONAR_ALTITUDE = readEEPROM(KI_SONAR_ALTITUDE_ADR);
|
||||
KD_SONAR_ALTITUDE = readEEPROM(KD_SONAR_ALTITUDE_ADR);
|
||||
}
|
||||
|
||||
void writeUserConfig() {
|
||||
// eeprom_counter = readEEPROM(eeprom_counter_ADR);
|
||||
// if(eeprom_counter > 0) eeprom_counter = 0;
|
||||
// eeprom_counter++;
|
||||
// writeEEPROM(eeprom_counter, eeprom_counter_ADR);
|
||||
writeEEPROM(KP_QUAD_ROLL, KP_QUAD_ROLL_ADR);
|
||||
writeEEPROM(KI_QUAD_ROLL, KI_QUAD_ROLL_ADR);
|
||||
writeEEPROM(STABLE_MODE_KP_RATE_ROLL, STABLE_MODE_KP_RATE_ROLL_ADR);
|
||||
writeEEPROM(KP_QUAD_PITCH, KP_QUAD_PITCH_ADR);
|
||||
writeEEPROM(KI_QUAD_PITCH, KI_QUAD_PITCH_ADR);
|
||||
writeEEPROM(STABLE_MODE_KP_RATE_PITCH, STABLE_MODE_KP_RATE_PITCH_ADR);
|
||||
writeEEPROM(KP_QUAD_YAW, KP_QUAD_YAW_ADR);
|
||||
writeEEPROM(KI_QUAD_YAW, KI_QUAD_YAW_ADR);
|
||||
writeEEPROM(STABLE_MODE_KP_RATE_YAW, STABLE_MODE_KP_RATE_YAW_ADR);
|
||||
writeEEPROM(STABLE_MODE_KP_RATE, STABLE_MODE_KP_RATE_ADR); // NOT USED NOW
|
||||
writeEEPROM(KP_GPS_ROLL, KP_GPS_ROLL_ADR);
|
||||
writeEEPROM(KD_GPS_ROLL, KD_GPS_ROLL_ADR);
|
||||
writeEEPROM(KI_GPS_ROLL, KI_GPS_ROLL_ADR);
|
||||
writeEEPROM(KP_GPS_PITCH, KP_GPS_PITCH_ADR);
|
||||
writeEEPROM(KD_GPS_PITCH, KD_GPS_PITCH_ADR);
|
||||
writeEEPROM(KI_GPS_PITCH, KI_GPS_PITCH_ADR);
|
||||
writeEEPROM(GPS_MAX_ANGLE, GPS_MAX_ANGLE_ADR);
|
||||
writeEEPROM(KP_ALTITUDE, KP_ALTITUDE_ADR);
|
||||
writeEEPROM(KD_ALTITUDE, KD_ALTITUDE_ADR);
|
||||
writeEEPROM(KI_ALTITUDE, KI_ALTITUDE_ADR);
|
||||
writeEEPROM(acc_offset_x, acc_offset_x_ADR);
|
||||
writeEEPROM(acc_offset_y, acc_offset_y_ADR);
|
||||
writeEEPROM(acc_offset_z, acc_offset_z_ADR);
|
||||
writeEEPROM(gyro_offset_roll, gyro_offset_roll_ADR);
|
||||
writeEEPROM(gyro_offset_pitch, gyro_offset_pitch_ADR);
|
||||
writeEEPROM(gyro_offset_yaw, gyro_offset_yaw_ADR);
|
||||
writeEEPROM(Kp_ROLLPITCH, Kp_ROLLPITCH_ADR);
|
||||
writeEEPROM(Ki_ROLLPITCH, Ki_ROLLPITCH_ADR);
|
||||
writeEEPROM(Kp_YAW, Kp_YAW_ADR);
|
||||
writeEEPROM(Ki_YAW, Ki_YAW_ADR);
|
||||
writeEEPROM(GEOG_CORRECTION_FACTOR, GEOG_CORRECTION_FACTOR_ADR);
|
||||
writeEEPROM(MAGNETOMETER, MAGNETOMETER_ADR);
|
||||
writeEEPROM(Kp_RateRoll, KP_RATEROLL_ADR);
|
||||
writeEEPROM(Ki_RateRoll, KI_RATEROLL_ADR);
|
||||
writeEEPROM(Kd_RateRoll, KD_RATEROLL_ADR);
|
||||
writeEEPROM(Kp_RatePitch, KP_RATEPITCH_ADR);
|
||||
writeEEPROM(Ki_RatePitch, KI_RATEPITCH_ADR);
|
||||
writeEEPROM(Kd_RatePitch, KD_RATEPITCH_ADR);
|
||||
writeEEPROM(Kp_RateYaw, KP_RATEYAW_ADR);
|
||||
writeEEPROM(Ki_RateYaw, KI_RATEYAW_ADR);
|
||||
writeEEPROM(Kd_RateYaw, KD_RATEYAW_ADR);
|
||||
writeEEPROM(xmitFactor, XMITFACTOR_ADR);
|
||||
writeEEPROM(roll_mid, CHROLL_MID);
|
||||
writeEEPROM(pitch_mid, CHPITCH_MID);
|
||||
writeEEPROM(yaw_mid, CHYAW_MID);
|
||||
writeEEPROM(ch_roll_slope, ch_roll_slope_ADR);
|
||||
writeEEPROM(ch_pitch_slope, ch_pitch_slope_ADR);
|
||||
writeEEPROM(ch_throttle_slope, ch_throttle_slope_ADR);
|
||||
writeEEPROM(ch_yaw_slope, ch_yaw_slope_ADR);
|
||||
writeEEPROM(ch_aux_slope, ch_aux_slope_ADR);
|
||||
writeEEPROM(ch_aux2_slope, ch_aux2_slope_ADR);
|
||||
writeEEPROM(ch_roll_offset, ch_roll_offset_ADR);
|
||||
writeEEPROM(ch_pitch_offset, ch_pitch_offset_ADR);
|
||||
writeEEPROM(ch_throttle_offset, ch_throttle_offset_ADR);
|
||||
writeEEPROM(ch_yaw_offset, ch_yaw_offset_ADR);
|
||||
writeEEPROM(ch_aux_offset, ch_aux_offset_ADR);
|
||||
writeEEPROM(ch_aux2_offset, ch_aux2_offset_ADR);
|
||||
writeEEPROM(cam_mode, cam_mode_ADR);
|
||||
writeEEPROM(mag_orientation, mag_orientation_ADR);
|
||||
writeEEPROM(mag_declination, mag_declination_ADR);
|
||||
writeEEPROM(mag_offset_x, mag_offset_x_ADR);
|
||||
writeEEPROM(mag_offset_y, mag_offset_y_ADR);
|
||||
writeEEPROM(mag_offset_z, mag_offset_z_ADR);
|
||||
writeEEPROM(MIN_THROTTLE, MIN_THROTTLE_ADR);
|
||||
writeEEPROM(KP_RF_ROLL,KP_RF_ROLL_ADR);
|
||||
writeEEPROM(KI_RF_ROLL,KI_RF_ROLL_ADR);
|
||||
writeEEPROM(KD_RF_ROLL,KD_RF_ROLL_ADR);
|
||||
writeEEPROM(KP_RF_PITCH,KP_RF_PITCH_ADR);
|
||||
writeEEPROM(KI_RF_PITCH,KI_RF_PITCH_ADR);
|
||||
writeEEPROM(KD_RF_PITCH,KD_RF_PITCH_ADR);
|
||||
writeEEPROM(RF_MAX_ANGLE,RF_MAX_ANGLE_ADR);
|
||||
writeEEPROM(RF_SAFETY_ZONE,RF_SAFETY_ZONE_ADR);
|
||||
writeEEPROM(KP_SONAR_ALTITUDE,KP_SONAR_ALTITUDE_ADR);
|
||||
writeEEPROM(KI_SONAR_ALTITUDE,KI_SONAR_ALTITUDE_ADR);
|
||||
writeEEPROM(KD_SONAR_ALTITUDE,KD_SONAR_ALTITUDE_ADR);
|
||||
}
|
@ -1,118 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Events.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
31-10-10 Moved camera stabilization from Functions to here, jp
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/* **************************************************** */
|
||||
// Camera stabilization
|
||||
//
|
||||
// Stabilization for three different camera styles
|
||||
// 1) Camera mounts that have tilt / pan
|
||||
// 2) Camera mounts that have tilt / roll
|
||||
// 3) Camera mounts that have tilt / roll / pan (future)
|
||||
//
|
||||
// Original code idea from Max Levine / DIY Drones
|
||||
// You need to initialize proper camera mode by sending Serial command and then save it
|
||||
// to EEPROM memory. Possible commands are K1, K2, K3, K4
|
||||
// Look more about different camera type on ArduCopter Wiki
|
||||
|
||||
#ifdef IsCAM
|
||||
void camera_output() {
|
||||
|
||||
// cam_mode = 1; // for debugging
|
||||
// Camera stabilization jump tables
|
||||
// SW_DIP1 is a multplier, settings
|
||||
switch ((SW_DIP1 * 4) + cam_mode + (BATTLOW * 10)) {
|
||||
// Cases 1 & 4 are stabilization for + Mode flying setup
|
||||
// Cases 5 & 8 are stabilization for x Mode flying setup
|
||||
|
||||
// Modes 3/4 + 7/8 needs still proper scaling on yaw movement
|
||||
// Scaling needs physical test flying with FPV cameras on, 30-10-10 jp
|
||||
|
||||
case 1:
|
||||
// Camera stabilization with Roll / Tilt mounts, NO transmitter input
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((CAM_CENT + (pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_ROLL_OUT, limitRange((CAM_CENT + (roll) * CAM_SMOOTHING_ROLL), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
case 2:
|
||||
// Camera stabilization with Roll / Tilt mounts, transmitter controls basic "zerolevel"
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((APM_RC.InputCh(CAM_TILT_CH) + (pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_ROLL_OUT, limitRange((CAM_CENT + (roll) * CAM_SMOOTHING_ROLL), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
case 3:
|
||||
// Camera stabilization with Yaw / Tilt mounts, NO transmitter input
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((CAM_CENT - (roll - pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_YAW_OUT, limitRange((CAM_CENT - (gyro_offset_yaw - AN[2])), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
case 4:
|
||||
// Camera stabilization with Yaw / Tilt mounts, transmitter controls basic "zerolevel"
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((APM_RC.InputCh(CAM_TILT_CH) + (pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_YAW_OUT, limitRange((CAM_CENT - (gyro_offset_yaw - AN[2])), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
|
||||
// x Mode flying setup
|
||||
case 5:
|
||||
// Camera stabilization with Roll / Tilt mounts, NO transmitter input
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((CAM_CENT - (roll - pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_ROLL_OUT, limitRange((CAM_CENT + (roll + pitch) * CAM_SMOOTHING), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
case 6:
|
||||
// Camera stabilization with Roll / Tilt mounts, transmitter controls basic "zerolevel"
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((APM_RC.InputCh(CAM_TILT_CH) + (roll - pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_ROLL_OUT, limitRange((CAM_CENT + (roll + pitch) * CAM_SMOOTHING), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
case 7:
|
||||
// Camera stabilization with Yaw / Tilt mounts, NO transmitter input
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((CAM_CENT - (roll - pitch) * CAM_SMOOTHING), 1000, 2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_YAW_OUT, limitRange((CAM_CENT - (gyro_offset_yaw - AN[2])), 1000, 2000)); // Roll correction
|
||||
break;
|
||||
case 8:
|
||||
// Camera stabilization with Yaw / Tilt mounts, transmitter controls basic "zerolevel"
|
||||
APM_RC.OutputCh(CAM_TILT_OUT, limitRange((APM_RC.InputCh(CAM_TILT_CH) - (roll - pitch) * CAM_SMOOTHING),1000,2000)); // Tilt correction
|
||||
APM_RC.OutputCh(CAM_YAW_OUT, limitRange((CAM_CENT - (gyro_offset_yaw - AN[2])),1000,2000)); // Yaw correction
|
||||
break;
|
||||
|
||||
// Only in case of we have switch values over 10
|
||||
default:
|
||||
// We should not be here...
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -1,186 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Functions.pde
|
||||
Version : v1.0, Aug 28, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
30-10-10 added basic camera stabilization functions with jumptables
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
|
||||
// Flash those A,B,C LEDs on IMU Board
|
||||
//
|
||||
// Function: FullBlink(int, int);
|
||||
// int 1 =
|
||||
void FullBlink(int count, int blinkdelay) {
|
||||
for(int i = 0; i <= count; i++) {
|
||||
digitalWrite(LED_Green, HIGH);
|
||||
digitalWrite(LED_Yellow, HIGH);
|
||||
digitalWrite(LED_Red, HIGH);
|
||||
delay(blinkdelay);
|
||||
digitalWrite(LED_Green, LOW);
|
||||
digitalWrite(LED_Yellow, LOW);
|
||||
digitalWrite(LED_Red, LOW);
|
||||
delay(blinkdelay);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void RunningLights(int LightStep) {
|
||||
|
||||
if(LightStep == 0) {
|
||||
digitalWrite(LED_Green, HIGH);
|
||||
digitalWrite(LED_Yellow, LOW);
|
||||
digitalWrite(LED_Red, LOW);
|
||||
}
|
||||
else if (LightStep == 1) {
|
||||
digitalWrite(LED_Green, LOW);
|
||||
digitalWrite(LED_Yellow, HIGH);
|
||||
digitalWrite(LED_Red, LOW);
|
||||
}
|
||||
else {
|
||||
digitalWrite(LED_Green, LOW);
|
||||
digitalWrite(LED_Yellow, LOW);
|
||||
digitalWrite(LED_Red, HIGH);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void LightsOff() {
|
||||
digitalWrite(LED_Green, LOW);
|
||||
digitalWrite(LED_Yellow, LOW);
|
||||
digitalWrite(LED_Red, LOW);
|
||||
}
|
||||
|
||||
// Funtion to normalize an angle in degrees to -180,180 degrees
|
||||
float Normalize_angle(float angle)
|
||||
{
|
||||
if (angle > 180)
|
||||
return (angle - 360.0);
|
||||
else if (angle < -180)
|
||||
return (angle + 360.0);
|
||||
else
|
||||
return(angle);
|
||||
}
|
||||
|
||||
// Maximun slope filter for radio inputs... (limit max differences between readings)
|
||||
int channel_filter(int ch, int ch_old)
|
||||
{
|
||||
int diff_ch_old;
|
||||
|
||||
if (ch_old==0) // ch_old not initialized
|
||||
return(ch);
|
||||
diff_ch_old = ch - ch_old; // Difference with old reading
|
||||
if (diff_ch_old < 0)
|
||||
{
|
||||
if (diff_ch_old <- 60)
|
||||
return(ch_old - 60); // We limit the max difference between readings
|
||||
}
|
||||
else
|
||||
{
|
||||
if (diff_ch_old > 60)
|
||||
return(ch_old + 60);
|
||||
}
|
||||
return((ch + ch_old) >> 1); // Small filtering
|
||||
//return(ch);
|
||||
}
|
||||
|
||||
|
||||
// Special APM PinMode settings and others
|
||||
void APMPinMode(volatile unsigned char &Port, byte Pin, boolean Set)
|
||||
{
|
||||
if (Set) {
|
||||
Port |= (1 << Pin);
|
||||
}
|
||||
else {
|
||||
Port &= ~(1 << Pin);
|
||||
}
|
||||
}
|
||||
|
||||
boolean APMPinRead(volatile unsigned char &Port, byte Pin)
|
||||
{
|
||||
if(Port & (1 << Pin))
|
||||
return 1;
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Faster and smaller replacement for contrain() function
|
||||
int limitRange(int data, int minLimit, int maxLimit) {
|
||||
if (data < minLimit) return minLimit;
|
||||
else if (data > maxLimit) return maxLimit;
|
||||
else return data;
|
||||
}
|
||||
|
||||
|
||||
// Stepping G, Y, R Leds
|
||||
// Call CLILedStep(); to change led statuses
|
||||
// Used on CLI as showing that we are in CLI mode
|
||||
void CLILedStep () {
|
||||
|
||||
switch(cli_step) {
|
||||
case 1:
|
||||
digitalWrite(LED_Green, HIGH);
|
||||
digitalWrite(LED_Yellow, LOW);
|
||||
digitalWrite(LED_Red, LOW);
|
||||
break;
|
||||
case 2:
|
||||
digitalWrite(LED_Green, LOW);
|
||||
digitalWrite(LED_Yellow, HIGH);
|
||||
digitalWrite(LED_Red, LOW);
|
||||
break;
|
||||
case 3:
|
||||
digitalWrite(LED_Green, LOW);
|
||||
digitalWrite(LED_Yellow, LOW);
|
||||
digitalWrite(LED_Red, HIGH);
|
||||
break;
|
||||
}
|
||||
cli_step ++;
|
||||
if(cli_step == 4) cli_step = 1;
|
||||
|
||||
}
|
||||
|
||||
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
|
||||
|
||||
|
||||
|
@ -1,521 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : GCS.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
//
|
||||
// Function : send_message()
|
||||
//
|
||||
// Parameters:
|
||||
// byte severity - Debug level
|
||||
// char str - Text to write
|
||||
//
|
||||
// Returns : - none
|
||||
|
||||
void send_message(byte severity, const char *str) // This is the instance of send_message for message 0x05
|
||||
{
|
||||
if(severity >= DEBUG_LEVEL){
|
||||
SerPri("MSG: ");
|
||||
SerPrln(str);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
// Function : readSerialCommand()
|
||||
//
|
||||
// Parameters:
|
||||
// - none
|
||||
//
|
||||
// Returns : - none
|
||||
//
|
||||
void readSerialCommand() {
|
||||
// Check for serial message
|
||||
if (SerAva()) {
|
||||
queryType = SerRea();
|
||||
switch (queryType) {
|
||||
case 'A': // Stable PID
|
||||
KP_QUAD_ROLL = readFloatSerial();
|
||||
KI_QUAD_ROLL = readFloatSerial();
|
||||
STABLE_MODE_KP_RATE_ROLL = readFloatSerial();
|
||||
KP_QUAD_PITCH = readFloatSerial();
|
||||
KI_QUAD_PITCH = readFloatSerial();
|
||||
STABLE_MODE_KP_RATE_PITCH = readFloatSerial();
|
||||
KP_QUAD_YAW = readFloatSerial();
|
||||
KI_QUAD_YAW = readFloatSerial();
|
||||
STABLE_MODE_KP_RATE_YAW = readFloatSerial();
|
||||
STABLE_MODE_KP_RATE = readFloatSerial(); // NOT USED NOW
|
||||
MAGNETOMETER = readFloatSerial();
|
||||
break;
|
||||
case 'C': // Receive GPS PID
|
||||
KP_GPS_ROLL = readFloatSerial();
|
||||
KI_GPS_ROLL = readFloatSerial();
|
||||
KD_GPS_ROLL = readFloatSerial();
|
||||
KP_GPS_PITCH = readFloatSerial();
|
||||
KI_GPS_PITCH = readFloatSerial();
|
||||
KD_GPS_PITCH = readFloatSerial();
|
||||
GPS_MAX_ANGLE = readFloatSerial();
|
||||
GEOG_CORRECTION_FACTOR = readFloatSerial();
|
||||
break;
|
||||
case 'E': // Receive altitude PID
|
||||
KP_ALTITUDE = readFloatSerial();
|
||||
KI_ALTITUDE = readFloatSerial();
|
||||
KD_ALTITUDE = readFloatSerial();
|
||||
break;
|
||||
case 'G': // Receive drift correction PID
|
||||
Kp_ROLLPITCH = readFloatSerial();
|
||||
Ki_ROLLPITCH = readFloatSerial();
|
||||
Kp_YAW = readFloatSerial();
|
||||
Ki_YAW = readFloatSerial();
|
||||
break;
|
||||
case 'I': // Receive sensor offset
|
||||
gyro_offset_roll = readFloatSerial();
|
||||
gyro_offset_pitch = readFloatSerial();
|
||||
gyro_offset_yaw = readFloatSerial();
|
||||
acc_offset_x = readFloatSerial();
|
||||
acc_offset_y = readFloatSerial();
|
||||
acc_offset_z = readFloatSerial();
|
||||
break;
|
||||
case 'K': // Camera mode
|
||||
// 1 = Tilt / Roll without
|
||||
cam_mode = readFloatSerial();
|
||||
//BATTLOW = readFloatSerial();
|
||||
break;
|
||||
case 'M': // Receive debug motor commands
|
||||
frontMotor = readFloatSerial();
|
||||
backMotor = readFloatSerial();
|
||||
rightMotor = readFloatSerial();
|
||||
leftMotor = readFloatSerial();
|
||||
motorArmed = readFloatSerial();
|
||||
break;
|
||||
case 'O': // Rate Control PID
|
||||
Kp_RateRoll = readFloatSerial();
|
||||
Ki_RateRoll = readFloatSerial();
|
||||
Kd_RateRoll = readFloatSerial();
|
||||
Kp_RatePitch = readFloatSerial();
|
||||
Ki_RatePitch = readFloatSerial();
|
||||
Kd_RatePitch = readFloatSerial();
|
||||
Kp_RateYaw = readFloatSerial();
|
||||
Ki_RateYaw = readFloatSerial();
|
||||
Kd_RateYaw = readFloatSerial();
|
||||
xmitFactor = readFloatSerial();
|
||||
break;
|
||||
case 'W': // Write all user configurable values to EEPROM
|
||||
writeUserConfig();
|
||||
break;
|
||||
case 'Y': // Initialize EEPROM with default values
|
||||
defaultUserConfig();
|
||||
#if AIRFRAME == HELI
|
||||
heli_defaultUserConfig();
|
||||
#endif
|
||||
break;
|
||||
case '1': // Receive transmitter calibration values
|
||||
ch_roll_slope = readFloatSerial();
|
||||
ch_roll_offset = readFloatSerial();
|
||||
ch_pitch_slope = readFloatSerial();
|
||||
ch_pitch_offset = readFloatSerial();
|
||||
ch_yaw_slope = readFloatSerial();
|
||||
ch_yaw_offset = readFloatSerial();
|
||||
ch_throttle_slope = readFloatSerial();
|
||||
ch_throttle_offset = readFloatSerial();
|
||||
ch_aux_slope = readFloatSerial();
|
||||
ch_aux_offset = readFloatSerial();
|
||||
ch_aux2_slope = readFloatSerial();
|
||||
ch_aux2_offset = readFloatSerial();
|
||||
break;
|
||||
case '5': // Special debug features
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void sendSerialTelemetry() {
|
||||
float aux_float[3]; // used for sensor calibration
|
||||
switch (queryType) {
|
||||
case '=': // Reserved debug command to view any variable from Serial Monitor
|
||||
/* SerPri(("throttle =");
|
||||
SerPrln(ch_throttle);
|
||||
SerPri("control roll =");
|
||||
SerPrln(control_roll-CHANN_CENTER);
|
||||
SerPri("control pitch =");
|
||||
SerPrln(control_pitch-CHANN_CENTER);
|
||||
SerPri("control yaw =");
|
||||
SerPrln(control_yaw-CHANN_CENTER);
|
||||
SerPri("front left yaw =");
|
||||
SerPrln(frontMotor);
|
||||
SerPri("front right yaw =");
|
||||
SerPrln(rightMotor);
|
||||
SerPri("rear left yaw =");
|
||||
SerPrln(leftMotor);
|
||||
SerPri("rear right motor =");
|
||||
SerPrln(backMotor);
|
||||
SerPrln();
|
||||
|
||||
SerPri("current roll rate =");
|
||||
SerPrln(read_adc(0));
|
||||
SerPri("current pitch rate =");
|
||||
SerPrln(read_adc(1));
|
||||
SerPri("current yaw rate =");
|
||||
SerPrln(read_adc(2));
|
||||
SerPri("command rx yaw =");
|
||||
SerPrln(command_rx_yaw);
|
||||
SerPrln();
|
||||
queryType = 'X';*/
|
||||
SerPri(APM_RC.InputCh(0));
|
||||
comma();
|
||||
SerPri(ch_roll_slope);
|
||||
comma();
|
||||
SerPri(ch_roll_offset);
|
||||
comma();
|
||||
SerPrln(ch_roll);
|
||||
break;
|
||||
case 'B': // Send roll, pitch and yaw PID values
|
||||
SerPri(KP_QUAD_ROLL, 3);
|
||||
comma();
|
||||
SerPri(KI_QUAD_ROLL, 3);
|
||||
comma();
|
||||
SerPri(STABLE_MODE_KP_RATE_ROLL, 3);
|
||||
comma();
|
||||
SerPri(KP_QUAD_PITCH, 3);
|
||||
comma();
|
||||
SerPri(KI_QUAD_PITCH, 3);
|
||||
comma();
|
||||
SerPri(STABLE_MODE_KP_RATE_PITCH, 3);
|
||||
comma();
|
||||
SerPri(KP_QUAD_YAW, 3);
|
||||
comma();
|
||||
SerPri(KI_QUAD_YAW, 3);
|
||||
comma();
|
||||
SerPri(STABLE_MODE_KP_RATE_YAW, 3);
|
||||
comma();
|
||||
SerPri(STABLE_MODE_KP_RATE, 3); // NOT USED NOW
|
||||
comma();
|
||||
SerPrln(MAGNETOMETER, 3);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'D': // Send GPS PID
|
||||
SerPri(KP_GPS_ROLL, 3);
|
||||
comma();
|
||||
SerPri(KI_GPS_ROLL, 3);
|
||||
comma();
|
||||
SerPri(KD_GPS_ROLL, 3);
|
||||
comma();
|
||||
SerPri(KP_GPS_PITCH, 3);
|
||||
comma();
|
||||
SerPri(KI_GPS_PITCH, 3);
|
||||
comma();
|
||||
SerPri(KD_GPS_PITCH, 3);
|
||||
comma();
|
||||
SerPri(GPS_MAX_ANGLE, 3);
|
||||
comma();
|
||||
SerPrln(GEOG_CORRECTION_FACTOR, 3);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'F': // Send altitude PID
|
||||
SerPri(KP_ALTITUDE, 3);
|
||||
comma();
|
||||
SerPri(KI_ALTITUDE, 3);
|
||||
comma();
|
||||
SerPrln(KD_ALTITUDE, 3);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'H': // Send drift correction PID
|
||||
SerPri(Kp_ROLLPITCH, 4);
|
||||
comma();
|
||||
SerPri(Ki_ROLLPITCH, 7);
|
||||
comma();
|
||||
SerPri(Kp_YAW, 4);
|
||||
comma();
|
||||
SerPrln(Ki_YAW, 6);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'J': // Send sensor offset
|
||||
SerPri(gyro_offset_roll);
|
||||
comma();
|
||||
SerPri(gyro_offset_pitch);
|
||||
comma();
|
||||
SerPri(gyro_offset_yaw);
|
||||
comma();
|
||||
SerPri(acc_offset_x);
|
||||
comma();
|
||||
SerPri(acc_offset_y);
|
||||
comma();
|
||||
SerPrln(acc_offset_z);
|
||||
AN_OFFSET[3] = acc_offset_x;
|
||||
AN_OFFSET[4] = acc_offset_y;
|
||||
AN_OFFSET[5] = acc_offset_z;
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'L': // Camera settings and
|
||||
SerPri(cam_mode, DEC);
|
||||
tab();
|
||||
SerPri(BATTLOW, DEC);
|
||||
tab();
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'N': // Send magnetometer config
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'P': // Send rate control PID
|
||||
SerPri(Kp_RateRoll, 3);
|
||||
comma();
|
||||
SerPri(Ki_RateRoll, 3);
|
||||
comma();
|
||||
SerPri(Kd_RateRoll, 3);
|
||||
comma();
|
||||
SerPri(Kp_RatePitch, 3);
|
||||
comma();
|
||||
SerPri(Ki_RatePitch, 3);
|
||||
comma();
|
||||
SerPri(Kd_RatePitch, 3);
|
||||
comma();
|
||||
SerPri(Kp_RateYaw, 3);
|
||||
comma();
|
||||
SerPri(Ki_RateYaw, 3);
|
||||
comma();
|
||||
SerPri(Kd_RateYaw, 3);
|
||||
comma();
|
||||
SerPrln(xmitFactor, 3);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case 'Q': // Send sensor data
|
||||
SerPri(read_adc(0));
|
||||
comma();
|
||||
SerPri(read_adc(1));
|
||||
comma();
|
||||
SerPri(read_adc(2));
|
||||
comma();
|
||||
SerPri(read_adc(4));
|
||||
comma();
|
||||
SerPri(read_adc(3));
|
||||
comma();
|
||||
SerPri(read_adc(5));
|
||||
comma();
|
||||
SerPri(err_roll);
|
||||
comma();
|
||||
SerPri(err_pitch);
|
||||
comma();
|
||||
SerPri(degrees(roll));
|
||||
comma();
|
||||
SerPri(degrees(pitch));
|
||||
comma();
|
||||
SerPrln(degrees(yaw));
|
||||
break;
|
||||
case 'R': // Send raw sensor data
|
||||
break;
|
||||
case 'S': // Send all flight data
|
||||
SerPri(timer-timer_old);
|
||||
comma();
|
||||
SerPri(read_adc(0));
|
||||
comma();
|
||||
SerPri(read_adc(1));
|
||||
comma();
|
||||
SerPri(read_adc(2));
|
||||
comma();
|
||||
SerPri(ch_throttle);
|
||||
comma();
|
||||
SerPri(control_roll);
|
||||
comma();
|
||||
SerPri(control_pitch);
|
||||
comma();
|
||||
SerPri(control_yaw);
|
||||
comma();
|
||||
SerPri(frontMotor); // Front Motor
|
||||
comma();
|
||||
SerPri(backMotor); // Back Motor
|
||||
comma();
|
||||
SerPri(rightMotor); // Right Motor
|
||||
comma();
|
||||
SerPri(leftMotor); // Left Motor
|
||||
comma();
|
||||
SerPri(read_adc(4));
|
||||
comma();
|
||||
SerPri(read_adc(3));
|
||||
comma();
|
||||
SerPri(read_adc(5));
|
||||
|
||||
comma();
|
||||
SerPri(AP_Compass.heading, 4);
|
||||
comma();
|
||||
SerPri(AP_Compass.heading_x, 4);
|
||||
comma();
|
||||
SerPri(AP_Compass.heading_y, 4);
|
||||
comma();
|
||||
SerPri(AP_Compass.mag_x);
|
||||
comma();
|
||||
SerPri(AP_Compass.mag_y);
|
||||
comma();
|
||||
SerPri(AP_Compass.mag_z);
|
||||
// comma();
|
||||
|
||||
SerPriln();
|
||||
break;
|
||||
case 'T': // Spare
|
||||
break;
|
||||
case 'U': // Send receiver values
|
||||
SerPri(ch_roll); // Aileron
|
||||
comma();
|
||||
SerPri(ch_pitch); // Elevator
|
||||
comma();
|
||||
SerPri(ch_yaw); // Yaw
|
||||
comma();
|
||||
SerPri(ch_throttle); // Throttle
|
||||
comma();
|
||||
SerPri(ch_aux); // AUX1 (Mode)
|
||||
comma();
|
||||
SerPri(ch_aux2); // AUX2
|
||||
comma();
|
||||
SerPri(roll_mid); // Roll MID value
|
||||
comma();
|
||||
SerPri(pitch_mid); // Pitch MID value
|
||||
comma();
|
||||
SerPrln(yaw_mid); // Yaw MID Value
|
||||
break;
|
||||
case 'V': // Spare
|
||||
break;
|
||||
case 'X': // Stop sending messages
|
||||
break;
|
||||
case '!': // Send flight software version
|
||||
SerPrln(VER);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case '2': // Send transmitter calibration values
|
||||
SerPri(ch_roll_slope);
|
||||
comma();
|
||||
SerPri(ch_roll_offset);
|
||||
comma();
|
||||
SerPri(ch_pitch_slope);
|
||||
comma();
|
||||
SerPri(ch_pitch_offset);
|
||||
comma();
|
||||
SerPri(ch_yaw_slope);
|
||||
comma();
|
||||
SerPri(ch_yaw_offset);
|
||||
comma();
|
||||
SerPri(ch_throttle_slope);
|
||||
comma();
|
||||
SerPri(ch_throttle_offset);
|
||||
comma();
|
||||
SerPri(ch_aux_slope);
|
||||
comma();
|
||||
SerPri(ch_aux_offset);
|
||||
comma();
|
||||
SerPri(ch_aux2_slope);
|
||||
comma();
|
||||
SerPrln(ch_aux2_offset);
|
||||
queryType = 'X';
|
||||
break;
|
||||
case '3': // Jani's debugs
|
||||
SerPri(yaw);
|
||||
tab();
|
||||
SerPri(command_rx_yaw);
|
||||
tab();
|
||||
SerPri(control_yaw);
|
||||
tab();
|
||||
SerPri(err_yaw);
|
||||
tab();
|
||||
SerPri(AN[0]);
|
||||
tab();
|
||||
SerPri(AN[1]);
|
||||
tab();
|
||||
SerPri(AN[2] - gyro_offset_yaw);
|
||||
tab();
|
||||
SerPri(gyro_offset_yaw - AN[2]);
|
||||
tab();
|
||||
SerPri(gyro_offset_yaw);
|
||||
tab();
|
||||
SerPri(1500 - (gyro_offset_yaw - AN[2]));
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
void comma() {
|
||||
SerPri(',');
|
||||
}
|
||||
|
||||
void tab() {
|
||||
SerPri("\t");
|
||||
}
|
||||
|
||||
// Used to read floating point values from the serial port
|
||||
float readFloatSerial() {
|
||||
byte index = 0;
|
||||
byte timeout = 0;
|
||||
char data[128] = "";
|
||||
|
||||
do {
|
||||
if (SerAva() == 0) {
|
||||
delay(10);
|
||||
timeout++;
|
||||
}
|
||||
else {
|
||||
data[index] = SerRea();
|
||||
timeout = 0;
|
||||
index++;
|
||||
}
|
||||
}
|
||||
while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
|
||||
return atof(data);
|
||||
}
|
||||
|
||||
|
@ -1,177 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Arducopter.h
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
#ifndef HELI_H
|
||||
#define HELI_H
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
#include "WProgram.h"
|
||||
#include <Wire.h>
|
||||
#include <EEPROM.h> // added by Randy
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Compass Library
|
||||
#include <DataFlash.h> // ArduPilot Mega DataFlash Library.
|
||||
#include "../AP_Math/AP_Math.h"
|
||||
|
||||
/**********************************************************************/
|
||||
// Channel definitions
|
||||
#define CHANNEL_FRONT_LEFT 0
|
||||
#define CHANNEL_FRONT_RIGHT 1
|
||||
#define CHANNEL_REAR 2
|
||||
#define CHANNEL_YAW 3
|
||||
|
||||
/**********************************************************************/
|
||||
// EEPROM locations
|
||||
#define EEPROM_BASE_ADDRESS 300
|
||||
#define EEPROM_MAGIC_NUMBER_ADDR EEPROM_BASE_ADDRESS
|
||||
#define FRONT_LEFT_CCPM_MIN_ADDR EEPROM_BASE_ADDRESS+4
|
||||
#define FRONT_LEFT_CCPM_MAX_ADDR EEPROM_BASE_ADDRESS+8
|
||||
#define FRONT_RIGHT_CCPM_MIN_ADDR EEPROM_BASE_ADDRESS+12
|
||||
#define FRONT_RIGHT_CCPM_MAX_ADDR EEPROM_BASE_ADDRESS+16
|
||||
#define REAR_CCPM_MIN_ADDR EEPROM_BASE_ADDRESS+20
|
||||
#define REAR_CCPM_MAX_ADDR EEPROM_BASE_ADDRESS+24
|
||||
#define YAW_MIN_ADDR EEPROM_BASE_ADDRESS+28
|
||||
#define YAW_MAX_ADDR EEPROM_BASE_ADDRESS+32
|
||||
#define THROTTLE_MIN_ADDR EEPROM_BASE_ADDRESS+36
|
||||
#define THROTTLE_MAX_ADDR EEPROM_BASE_ADDRESS+40
|
||||
|
||||
#define EEPROM_MAGIC_NUMBER 12345.0
|
||||
|
||||
#define YAW_MODE_HEADING_HOLD 0
|
||||
#define YAW_MODE_RATE 1
|
||||
|
||||
#define HELI_STICK_TO_ANGLE_FACTOR 2.0 // To convert ccpm values (-50 ~ 50 ) to absolute angles. larger number means less lean
|
||||
#define HELI_YAW_STICK_TO_ANGLE_FACTOR 0.5 // convert yaw (-50 ~ 50) to turn rate in degrees per second. larger number means slower turn rate
|
||||
|
||||
// CCPM Types
|
||||
#define HELI_CCPM_120_TWO_FRONT_ONE_BACK 0
|
||||
#define HELI_CCPM_120_ONE_FRONT_TWO_BACK 1
|
||||
|
||||
// define which CCPM we have
|
||||
#define HELI_CCPM HELI_CCPM_120_TWO_FRONT_ONE_BACK
|
||||
|
||||
// define DeAllocation matrix(converts radio inputs to roll, pitch and collective
|
||||
// for example roll = (inputCh0*Row1Col1) + (inputCh1*Row1Col2) + (inputCh2*Row1Col3)
|
||||
// pitch = (inputCh0*Row2Col1) + (inputCh1*Row2Col2) + (inputCh2*Row2Col3)
|
||||
// collective = (inputCh0*Row3Col1) + (inputCh1*Row3Col2) + (inputCh2*Row3Col3)
|
||||
// and Allocation matrix (converts roll, pitch, collective to servo outputs)
|
||||
// for example servo0 = (roll*Row1Col1) + (pitch*Row1Col2) + (collective*Row1Col3)
|
||||
// servo1 = (roll*Row2Col1) + (pitch*Row2Col2) + (collective*Row2Col3)
|
||||
// servo2 = (roll*Row3Col1) + (pitch*Row3Col2) + (collective*Row3Col3)
|
||||
#if HELI_CCPM == HELI_CCPM_120_TWO_FRONT_ONE_BACK
|
||||
#define CCPM_DEALLOCATION 0.5774, -0.5774, 0.0000, \
|
||||
0.3333, 0.3333, -0.6667, \
|
||||
0.3333, 0.3333, 0.3333
|
||||
#define CCPM_ALLOCATION 0.8660,0.5000, 1.0000, \
|
||||
-0.8660, 0.5000, 1.0000, \
|
||||
0.0000, -1.0000, 1.0000
|
||||
#endif
|
||||
|
||||
#if HELI_CCPM == HELI_CCPM_120_ONE_FRONT_TWO_BACK
|
||||
#define CCPM_DEALLOCATION 0.5774, -0.5774, 0.0000, \
|
||||
-0.3333,-0.3333, 0.6667, \
|
||||
0.3333, 0.3333, 0.3333
|
||||
#define CCPM_ALLOCATION 0.8660, -0.5000, 1.0000, \
|
||||
-0.8660, -0.5000, 1.0000, \
|
||||
0.0000, 1.0000, 1.0000
|
||||
#endif
|
||||
|
||||
const Matrix3f ccpmDeallocation(CCPM_DEALLOCATION);
|
||||
const Matrix3f ccpmAllocation(CCPM_ALLOCATION);
|
||||
|
||||
/**********************************************************************/
|
||||
// time variables - we run at a different hertz than quads
|
||||
unsigned long heli_previousTimeMicros = 0;
|
||||
|
||||
// PWM Input Processing - Variable Definitions
|
||||
float frontLeftCCPMmin;
|
||||
float frontLeftCCPMmax;
|
||||
float frontLeftCCPMslope;
|
||||
float frontLeftCCPMintercept;
|
||||
|
||||
float frontRightCCPMmin;
|
||||
float frontRightCCPMmax;
|
||||
float frontRightCCPMslope;
|
||||
float frontRightCCPMintercept;
|
||||
|
||||
float rearCCPMmin;
|
||||
float rearCCPMmax;
|
||||
float rearCCPMslope;
|
||||
float rearCCPMintercept;
|
||||
|
||||
float yawMin;
|
||||
float yawMax;
|
||||
float yawSlope;
|
||||
float yawIntercept;
|
||||
|
||||
Vector3f ccpmPercents; // Array of ccpm input values, converted to percents
|
||||
Vector3f rollPitchCollPercent; // Array containing deallocated roll, pitch and collective percent commands
|
||||
float ch_collective;
|
||||
int collective_mid;
|
||||
float control_collective;
|
||||
float command_rx_collective;
|
||||
float yawPercent;
|
||||
float targetHeading;
|
||||
|
||||
// trims
|
||||
float trim_roll = 0.0;
|
||||
float trim_pitch = 0.0;
|
||||
float trim_yaw = 0.0;
|
||||
|
||||
// axis under APM control
|
||||
int roll_control_switch = 1;
|
||||
int pitch_control_switch = 1;
|
||||
int yaw_control_switch = 1;
|
||||
int collective_control_switch = 0;
|
||||
//int position_control_switch = 0;
|
||||
//int position_control_engaged = 0; // we don't have enough buttons so we will turn this on and off with roll + pitch positions
|
||||
//int position_control_safety = 0; // if 0 then safety is off. if 1 then safety is on and position control will not operate
|
||||
|
||||
/// for sending values out to servos
|
||||
Vector3f ccpmPercents_out; // Array of ccpm input values, converted to percents
|
||||
Vector3f pitchRollCollPercent_out; // Array containing deallocated pitch, roll, and collective percent commands
|
||||
|
||||
// heli debug
|
||||
int heli_debug = 0;
|
||||
|
||||
/**********************************************************************/
|
||||
// Output to Servos
|
||||
int leftOut;
|
||||
int rightOut;
|
||||
int rearOut;
|
||||
int yawOut;
|
||||
|
||||
#endif HELI_H
|
@ -1,428 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Heli.pde
|
||||
Desc : code specific to traditional helicopters
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
#if AIRFRAME == HELI
|
||||
|
||||
/**********************************************************************/
|
||||
// heli_readUserConfig - reads values in from EEPROM
|
||||
void heli_readUserConfig()
|
||||
{
|
||||
float magicNum = 0;
|
||||
magicNum = readEEPROM(EEPROM_MAGIC_NUMBER_ADDR);
|
||||
if( magicNum != EEPROM_MAGIC_NUMBER ) {
|
||||
SerPri("No heli settings found in EEPROM. Using defaults");
|
||||
heli_defaultUserConfig();
|
||||
}else{
|
||||
frontLeftCCPMmin = readEEPROM(FRONT_LEFT_CCPM_MIN_ADDR);
|
||||
frontLeftCCPMmax = readEEPROM(FRONT_LEFT_CCPM_MAX_ADDR);
|
||||
frontRightCCPMmin = readEEPROM(FRONT_RIGHT_CCPM_MIN_ADDR);
|
||||
frontRightCCPMmax = readEEPROM(FRONT_RIGHT_CCPM_MAX_ADDR);
|
||||
rearCCPMmin = readEEPROM(REAR_CCPM_MIN_ADDR);
|
||||
rearCCPMmax = readEEPROM(REAR_CCPM_MAX_ADDR);
|
||||
yawMin = readEEPROM(YAW_MIN_ADDR);
|
||||
yawMax = readEEPROM(YAW_MAX_ADDR);
|
||||
}
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
// default the heli specific values to defaults
|
||||
void heli_defaultUserConfig()
|
||||
{
|
||||
// default CCPM values.
|
||||
frontLeftCCPMmin = 1200;
|
||||
frontLeftCCPMmax = 1800;
|
||||
frontRightCCPMmin = 1900;
|
||||
frontRightCCPMmax = 1100;
|
||||
rearCCPMmin = 1200;
|
||||
rearCCPMmax = 1800;
|
||||
yawMin = 1200;
|
||||
yawMax = 1800;
|
||||
|
||||
// default PID values - Roll
|
||||
KP_QUAD_ROLL = 1.100;
|
||||
KI_QUAD_ROLL = 0.200;
|
||||
STABLE_MODE_KP_RATE_ROLL = -0.001;
|
||||
|
||||
// default PID values - Pitch
|
||||
KP_QUAD_PITCH = 1.100;
|
||||
KI_QUAD_PITCH = 0.120;
|
||||
STABLE_MODE_KP_RATE_PITCH = -0.001;
|
||||
|
||||
// default PID values - Yaw
|
||||
Kp_RateYaw = 3.500; // heading P term
|
||||
Ki_RateYaw = 0.100; // heading I term
|
||||
KP_QUAD_YAW = 0.200; // yaw rate P term
|
||||
KI_QUAD_YAW = 0.040; // yaw rate I term
|
||||
STABLE_MODE_KP_RATE_YAW = -0.010; // yaw rate D term
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
// displaySettings - displays heli specific user settings
|
||||
void heli_displaySettings()
|
||||
{
|
||||
SerPri("frontLeftCCPM min: ");
|
||||
SerPri(frontLeftCCPMmin);
|
||||
SerPri("\tmax:");
|
||||
SerPri(frontLeftCCPMmax);
|
||||
|
||||
if( abs(frontLeftCCPMmin-frontLeftCCPMmax)<50 || frontLeftCCPMmin < 900 || frontLeftCCPMmin > 2100 || frontLeftCCPMmax < 900 || frontLeftCCPMmax > 2100 )
|
||||
SerPrln("\t\t<-- check");
|
||||
else
|
||||
SerPrln();
|
||||
|
||||
SerPri("frontRightCCPM min: ");
|
||||
SerPri(frontRightCCPMmin);
|
||||
SerPri("\tmax:");
|
||||
SerPri(frontRightCCPMmax);
|
||||
if( abs(frontRightCCPMmin-frontRightCCPMmax)<50 || frontRightCCPMmin < 900 || frontRightCCPMmin > 2100 || frontRightCCPMmax < 900 || frontRightCCPMmax > 2100 )
|
||||
SerPrln("\t\t<-- check");
|
||||
else
|
||||
SerPrln();
|
||||
|
||||
SerPri("rearCCPM min: ");
|
||||
SerPri(rearCCPMmin);
|
||||
SerPri("\tmax:");
|
||||
SerPri(rearCCPMmax);
|
||||
if( abs(rearCCPMmin-rearCCPMmax)<50 || rearCCPMmin < 900 || rearCCPMmin > 2100 || rearCCPMmax < 900 || rearCCPMmax > 2100 )
|
||||
SerPrln("\t\t<-- check");
|
||||
else
|
||||
SerPrln();
|
||||
|
||||
SerPri("yaw min: ");
|
||||
SerPri(yawMin);
|
||||
SerPri("\tmax:");
|
||||
SerPri(yawMax);
|
||||
if( abs(yawMin-yawMax)<50 || yawMin < 900 || yawMin > 2100 || yawMax < 900 || yawMax > 2100 )
|
||||
SerPrln("\t\t<-- check");
|
||||
else
|
||||
SerPrln();
|
||||
|
||||
SerPrln();
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Setup Procedure
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
void heli_setup()
|
||||
{
|
||||
// read heli specific settings (like CCPM values) from EEPROM
|
||||
heli_readUserConfig();
|
||||
|
||||
// update CCPM values
|
||||
frontLeftCCPMslope = 100 / (frontLeftCCPMmax - frontLeftCCPMmin);
|
||||
frontLeftCCPMintercept = 100 - (frontLeftCCPMslope * frontLeftCCPMmax);
|
||||
frontRightCCPMslope = 100 / (frontRightCCPMmax - frontRightCCPMmin);
|
||||
frontRightCCPMintercept = 100 - (frontRightCCPMslope * frontRightCCPMmax);
|
||||
rearCCPMslope = 100 / (rearCCPMmax - rearCCPMmin);
|
||||
rearCCPMintercept = 100 - (rearCCPMslope * rearCCPMmax);
|
||||
yawSlope = 100 / (yawMax - yawMin);
|
||||
yawIntercept = 50 - (yawSlope * yawMax);
|
||||
|
||||
// capture trims
|
||||
heli_read_radio_trims();
|
||||
|
||||
// hardcode mids because we will use ccpm
|
||||
roll_mid = ROLL_MID;
|
||||
pitch_mid = PITCH_MID;
|
||||
collective_mid = 1500;
|
||||
yaw_mid = (yawMin+yawMax)/2;
|
||||
|
||||
// determine which axis APM will control
|
||||
roll_control_switch = !SW_DIP1;
|
||||
pitch_control_switch = !SW_DIP2;
|
||||
yaw_control_switch = !SW_DIP3;
|
||||
collective_control_switch = !SW_DIP4;
|
||||
//position_control_switch = !SW_DIP4; // switch 4 controls whether we will do GPS hold or not
|
||||
}
|
||||
|
||||
/*****************************************************************************************************/
|
||||
// heli_read_radio_trims - captures roll, pitch and yaw trims (mids) although only yaw is actually used
|
||||
// trim_yaw is used to center output to the tail which tends to be far from the
|
||||
// physical middle of where the rudder can move. This helps keep the PID's I
|
||||
// value low and avoid sudden turns left on takeoff
|
||||
void heli_read_radio_trims()
|
||||
{
|
||||
int i;
|
||||
float sumRoll = 0, sumPitch = 0, sumYaw = 0;
|
||||
|
||||
// initialiase trims to zero incase this is called more than once
|
||||
trim_roll = 0.0;
|
||||
trim_pitch = 0.0;
|
||||
trim_yaw = 0.0;
|
||||
|
||||
// read radio a few times
|
||||
for(int i=0; i<10; i++ )
|
||||
{
|
||||
// make sure new data has arrived
|
||||
while( APM_RC.GetState() != 1 )
|
||||
{
|
||||
delay(20);
|
||||
}
|
||||
heli_read_radio();
|
||||
sumRoll += ch_roll;
|
||||
sumPitch += ch_pitch;
|
||||
sumYaw += ch_yaw;
|
||||
}
|
||||
|
||||
// set trim to average
|
||||
trim_roll = sumRoll / 10.0;
|
||||
trim_pitch = sumPitch / 10.0;
|
||||
trim_yaw = sumYaw / 10.0;
|
||||
|
||||
// double check all is ok
|
||||
if( trim_roll > 50.0 || trim_roll < -50 )
|
||||
trim_roll = 0.0;
|
||||
if( trim_pitch >50.0 || trim_roll < -50.0 )
|
||||
trim_pitch = 0.0;
|
||||
if( trim_yaw > 50.0 || trim_yaw < -50.0 )
|
||||
trim_yaw = 0.0;
|
||||
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
// Radio decoding
|
||||
void heli_read_radio()
|
||||
{
|
||||
// left channel
|
||||
ccpmPercents.x = frontLeftCCPMslope * APM_RC.InputCh(CHANNEL_FRONT_LEFT) + frontLeftCCPMintercept;
|
||||
|
||||
// right channel
|
||||
ccpmPercents.y = frontRightCCPMslope * APM_RC.InputCh(CHANNEL_FRONT_RIGHT) + frontRightCCPMintercept;
|
||||
|
||||
// rear channel
|
||||
ccpmPercents.z = rearCCPMslope * APM_RC.InputCh(CHANNEL_REAR) + rearCCPMintercept;
|
||||
|
||||
// decode the ccpm
|
||||
rollPitchCollPercent = ccpmDeallocation * ccpmPercents;
|
||||
|
||||
// get the yaw (not coded)
|
||||
yawPercent = (yawSlope * APM_RC.InputCh(CHANNEL_YAW) + yawIntercept) - trim_yaw;
|
||||
|
||||
// put decoded values into the global variables
|
||||
ch_roll = rollPitchCollPercent.x;
|
||||
ch_pitch = rollPitchCollPercent.y;
|
||||
ch_collective = rollPitchCollPercent.z;
|
||||
|
||||
// allow a bit of a dead zone for the yaw
|
||||
if( fabs(yawPercent) < 2 )
|
||||
ch_yaw = 0;
|
||||
else
|
||||
ch_yaw = yawPercent;
|
||||
|
||||
// get the aux channel (for tuning on/off autopilot)
|
||||
ch_aux = APM_RC.InputCh(CH_5) * ch_aux_slope + ch_aux_offset;
|
||||
|
||||
// convert to absolute angles
|
||||
command_rx_roll = ch_roll / HELI_STICK_TO_ANGLE_FACTOR; // Convert stick position to absolute angles
|
||||
command_rx_pitch = ch_pitch / HELI_STICK_TO_ANGLE_FACTOR; // Convert stick position to absolute angles
|
||||
command_rx_collective = ch_collective;
|
||||
command_rx_yaw = ch_yaw / HELI_YAW_STICK_TO_ANGLE_FACTOR; // Convert stick position to turn rate
|
||||
|
||||
// for use by non-heli parts of code
|
||||
ch_throttle = 1000 + (ch_collective * 10);
|
||||
|
||||
// hardcode flight mode
|
||||
flightMode = STABLE_MODE;
|
||||
|
||||
// Autopilot mode (only works on Stable mode)
|
||||
if (flightMode == STABLE_MODE)
|
||||
{
|
||||
if(ch_aux < 1300) {
|
||||
AP_mode = AP_AUTOMATIC_MODE; // Automatic mode : GPS position hold mode + altitude hold
|
||||
//SerPrln("autopilot ON!");
|
||||
}else{
|
||||
AP_mode = AP_NORMAL_MODE; // Normal mode
|
||||
//SerPrln("autopilot OFF!");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
// output to swash plate based on control variables
|
||||
// Uses these global variables:
|
||||
// control_roll : -50 ~ 50
|
||||
// control_pitch : -50 ~ 50
|
||||
// control_collective : 0 ~ 100
|
||||
// control_yaw : -50 ~ 50
|
||||
void heli_moveSwashPlate()
|
||||
{
|
||||
static int count = 0;
|
||||
// turn pitch, roll, collective commands into ccpm values (i.e. values for each servo)
|
||||
ccpmPercents_out = ccpmAllocation * Vector3f(control_roll, control_pitch, control_collective);
|
||||
|
||||
// calculate values to be sent out to RC Output channels
|
||||
leftOut = (ccpmPercents_out.x - frontLeftCCPMintercept) / frontLeftCCPMslope;
|
||||
rightOut = (ccpmPercents_out.y - frontRightCCPMintercept) / frontRightCCPMslope;
|
||||
rearOut = (ccpmPercents_out.z - rearCCPMintercept) / rearCCPMslope;
|
||||
yawOut = (control_yaw - yawIntercept) / yawSlope;
|
||||
|
||||
APM_RC.OutputCh(CHANNEL_FRONT_LEFT,leftOut);
|
||||
APM_RC.OutputCh(CHANNEL_FRONT_RIGHT,rightOut);
|
||||
APM_RC.OutputCh(CHANNEL_REAR,rearOut);
|
||||
APM_RC.OutputCh(CHANNEL_YAW,yawOut);
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
// ROLL, PITCH and YAW PID controls...
|
||||
// Input : desired Roll, Pitch absolute angles
|
||||
// collective as a percentage from 0~100
|
||||
// yaw as a rate of rotation
|
||||
// Output : control_roll - roll servo as a percentage (-50 to 50)
|
||||
// control_pitch - pitch servo as a percentage (-50 to 50)
|
||||
// control_collective - collective servo as a percentage (0 to 100)
|
||||
// control_yaw - yaw servo as a percentage (0 to 100)
|
||||
void heli_attitude_control(int command_roll, int command_pitch, int command_collective, int command_yaw)
|
||||
{
|
||||
static float firstIteration = 1;
|
||||
static float command_yaw_previous = 0;
|
||||
static float previousYawRate = 0;
|
||||
float stable_roll, stable_pitch;
|
||||
float currentYawRate;
|
||||
float control_yaw_rate;
|
||||
float err_heading;
|
||||
static int aCounter = 0;
|
||||
float heli_G_Dt;
|
||||
|
||||
// get current time
|
||||
heli_G_Dt = (currentTimeMicros-heli_previousTimeMicros) * 0.000001; // Microseconds!!!
|
||||
heli_previousTimeMicros = currentTimeMicros;
|
||||
|
||||
// always pass through collective command
|
||||
control_collective = command_collective;
|
||||
|
||||
// ROLL CONTROL -- ONE PID
|
||||
if( roll_control_switch )
|
||||
{
|
||||
// P term
|
||||
err_roll = command_roll - ToDeg(roll);
|
||||
err_roll = constrain(err_roll,-25,25); // to limit max roll command...
|
||||
// I term
|
||||
roll_I += err_roll*heli_G_Dt*KI_QUAD_ROLL;
|
||||
roll_I = constrain(roll_I,-10,10);
|
||||
// D term
|
||||
roll_D = ToDeg(Omega[0]) * STABLE_MODE_KP_RATE_ROLL; // Take into account Angular velocity
|
||||
roll_D = constrain(roll_D,-25,25);
|
||||
|
||||
// PID control
|
||||
control_roll = KP_QUAD_ROLL*err_roll + roll_I + roll_D;
|
||||
control_roll = constrain(control_roll,-50,50);
|
||||
}else{
|
||||
// straight pass through
|
||||
control_roll = ch_roll;
|
||||
}
|
||||
|
||||
// PITCH CONTROL -- ONE PIDS
|
||||
if( pitch_control_switch )
|
||||
{
|
||||
// P term
|
||||
err_pitch = command_pitch - ToDeg(pitch);
|
||||
err_pitch = constrain(err_pitch,-25,25); // to limit max pitch command...
|
||||
// I term
|
||||
pitch_I += err_pitch * heli_G_Dt * KI_QUAD_PITCH;
|
||||
pitch_I = constrain(pitch_I,-10,10);
|
||||
// D term
|
||||
pitch_D = ToDeg(Omega[1]) * STABLE_MODE_KP_RATE_PITCH; // Take into account Angular velocity
|
||||
pitch_D = constrain(pitch_D,-25,25);
|
||||
// PID control
|
||||
control_pitch = KP_QUAD_PITCH*err_pitch + pitch_I + pitch_D;
|
||||
control_pitch = constrain(control_pitch,-50,50);
|
||||
}else{
|
||||
control_pitch = ch_pitch;
|
||||
}
|
||||
|
||||
// YAW CONTROL
|
||||
if( yaw_control_switch )
|
||||
{
|
||||
if( command_yaw == 0 ) // heading hold mode
|
||||
{
|
||||
// check we don't need to reset targetHeading
|
||||
if( command_yaw_previous != 0 )
|
||||
targetHeading = ToDeg(yaw);
|
||||
|
||||
// ensure reasonable targetHeading
|
||||
if( firstIteration || targetHeading > 180 || targetHeading < -180 )
|
||||
{
|
||||
firstIteration = 0;
|
||||
targetHeading = ToDeg(yaw);
|
||||
}
|
||||
|
||||
err_heading = Normalize_angle(targetHeading - ToDeg(yaw));
|
||||
err_heading = constrain(err_heading,-90,90); // don't make it travel any faster beyond 90 degrees
|
||||
|
||||
// I term
|
||||
heading_I += err_heading * heli_G_Dt * Ki_RateYaw;
|
||||
heading_I = constrain(heading_I,-20,20);
|
||||
|
||||
// PID control - a bit bad - we're using the acro mode's PID values because there's not PID for heading
|
||||
control_yaw_rate = Kp_RateYaw*err_heading + heading_I;
|
||||
control_yaw_rate = constrain(control_yaw_rate,-100,100); // to limit max yaw command
|
||||
}else{ // rate mode
|
||||
err_heading = 0;
|
||||
control_yaw_rate = command_yaw;
|
||||
}
|
||||
command_yaw_previous = command_yaw;
|
||||
|
||||
// YAW RATE CONTROL
|
||||
currentYawRate = ToDeg(Gyro_Scaled_Z(read_adc(2)));
|
||||
//currentYawRate = ToDeg(Omega_Vector[2]); <-- makes things very unstable!!
|
||||
err_yaw = control_yaw_rate-currentYawRate;
|
||||
|
||||
// I term
|
||||
yaw_I += err_yaw * heli_G_Dt * KI_QUAD_YAW;
|
||||
yaw_I = constrain(yaw_I, -20, 20);
|
||||
// D term
|
||||
yaw_D = (currentYawRate-previousYawRate) * STABLE_MODE_KP_RATE_YAW; // Take into account the change in angular velocity
|
||||
yaw_D = constrain(yaw_D,-25,25);
|
||||
previousYawRate = currentYawRate;
|
||||
|
||||
// PID control
|
||||
control_yaw = trim_yaw + (KP_QUAD_YAW*err_yaw + yaw_I + yaw_D); // add back in the yaw trim so that it is our center point
|
||||
control_yaw = constrain(control_yaw,-50,50);
|
||||
}else{
|
||||
// straight pass through
|
||||
control_yaw = ch_yaw;
|
||||
}
|
||||
|
||||
Log_Write_PID(7,KP_QUAD_ROLL*err_roll,roll_I,roll_D,control_roll);
|
||||
Log_Write_PID(8,KP_QUAD_PITCH*err_pitch,pitch_I,pitch_D,control_pitch);
|
||||
Log_Write_PID(9,Kp_RateYaw*err_heading,heading_I,0,control_yaw_rate);
|
||||
Log_Write_PID(10,KP_QUAD_YAW*err_yaw,yaw_I,yaw_D,control_yaw);
|
||||
}
|
||||
|
||||
#endif // #if AIRFRAME == HELI
|
@ -1,659 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Log.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
|
||||
// Code to Write and Read packets from DataFlash log memory
|
||||
// Code to interact with the user to dump or erase logs
|
||||
|
||||
#define HEAD_BYTE1 0xA3 // Decimal 163
|
||||
#define HEAD_BYTE2 0x95 // Decimal 149
|
||||
#define END_BYTE 0xBA // Decimal 186
|
||||
|
||||
#define LOG_ATTITUDE_MSG 0x01
|
||||
#define LOG_GPS_MSG 0x02
|
||||
#define LOG_MODE_MSG 0X03
|
||||
#define LOG_CONTROL_TUNING_MSG 0X04
|
||||
#define LOG_NAV_TUNING_MSG 0X05
|
||||
#define LOG_PERFORMANCE_MSG 0X06
|
||||
#define LOG_RAW_MSG 0x07
|
||||
#define LOG_RADIO_MSG 0x08
|
||||
#define LOG_SENSOR_MSG 0x09
|
||||
#define LOG_PID_MSG 0x0A
|
||||
#define LOG_RANGEFINDER_MSG 0x0B
|
||||
|
||||
#define LOG_MAX_ERRORS 50 // when reading logs, give up after 50 sequential failures to find HEADBYTE1
|
||||
|
||||
void Log_Erase(void)
|
||||
{
|
||||
SerPri("Erasing logs...");
|
||||
for(int i=0; i<4000; i++ )
|
||||
DataFlash.PageErase(i);
|
||||
SerPrln("Done!");
|
||||
}
|
||||
|
||||
|
||||
// Function to display available logs and solicit action from the user.
|
||||
// --------------------------------------------------------------------
|
||||
void Print_Log_Menu(void)
|
||||
{
|
||||
int log_start;
|
||||
int log_end;
|
||||
eeprom_busy_wait();
|
||||
byte last_log_num = eeprom_read_byte((uint8_t *) EE_LAST_LOG_NUM); eeprom_busy_wait();
|
||||
if (last_log_num == 0) {
|
||||
SerPriln("No logs available for download");
|
||||
} else {
|
||||
SerPri(last_log_num,DEC);
|
||||
SerPriln(" logs available for download");
|
||||
for(int i=1;i<last_log_num+1;i++) {
|
||||
log_start = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(i-1)*0x02)); eeprom_busy_wait();
|
||||
log_end = eeprom_read_word((uint16_t *) (EE_LOG_1_START+(i)*0x02))-1; eeprom_busy_wait();
|
||||
if (i == last_log_num) {
|
||||
log_end = eeprom_read_word((uint16_t *) EE_LAST_LOG_PAGE); eeprom_busy_wait();
|
||||
}
|
||||
SerPri("Log number ");
|
||||
SerPri(i);
|
||||
SerPri(", start page ");
|
||||
SerPri(log_start);
|
||||
SerPri(", end page ");
|
||||
SerPriln(log_end);
|
||||
}
|
||||
}
|
||||
SerPriln(" ");
|
||||
SerPriln("Input 1 <enter> to dump a log");
|
||||
SerPriln("Input 2 <enter> to erase all logs");
|
||||
SerPriln("Input 3 <enter> to leave log mode");
|
||||
SerPriln(" ");
|
||||
}
|
||||
|
||||
|
||||
// Function to get desired action from the user.
|
||||
// ---------------------------------------------
|
||||
byte Get_User_Log_Command(void)
|
||||
{
|
||||
|
||||
byte step=0;
|
||||
byte char_1;
|
||||
byte char_2;
|
||||
byte char_3;
|
||||
|
||||
Serial.flush();
|
||||
|
||||
while(step<3)
|
||||
{
|
||||
if(Serial.available()){
|
||||
char_1 = Serial.read();
|
||||
char_2 = Serial.read();
|
||||
char_3 = Serial.read();
|
||||
|
||||
if (char_1<0x30 || char_1>0x39) {
|
||||
return 0;
|
||||
} else if (char_2 == 0xFF) {
|
||||
return (char_1 - 0x30);
|
||||
} else if (char_2<0x30 || char_2>0x39) {
|
||||
return 0;
|
||||
} else if (char_2 != 0xFF) {
|
||||
return 0;
|
||||
} else {
|
||||
return ((char_1 - 0x30)*10 + char_2 - 0x30);
|
||||
}
|
||||
|
||||
} else {
|
||||
delay(20);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Write an attitude packet. Total length : 10 bytes
|
||||
#if LOG_ATTITUDE
|
||||
void Log_Write_Attitude(int log_roll, int log_pitch, int log_yaw)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_ATTITUDE_MSG);
|
||||
DataFlash.WriteInt(log_roll);
|
||||
DataFlash.WriteInt(log_pitch);
|
||||
DataFlash.WriteInt(log_yaw);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef LOG_SEN
|
||||
// Write a Sensor Raw data packet
|
||||
void Log_Write_Sensor(int s1, int s2, int s3,int s4, int s5, int s6, int s7)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_SENSOR_MSG);
|
||||
DataFlash.WriteInt(s1);
|
||||
DataFlash.WriteInt(s2);
|
||||
DataFlash.WriteInt(s3);
|
||||
DataFlash.WriteInt(s4);
|
||||
DataFlash.WriteInt(s5);
|
||||
DataFlash.WriteInt(s6);
|
||||
DataFlash.WriteInt(s7);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Write a PID control info
|
||||
void Log_Write_PID(byte num_PID, int P, int I,int D, int output)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_PID_MSG);
|
||||
DataFlash.WriteByte(num_PID);
|
||||
DataFlash.WriteInt(P);
|
||||
DataFlash.WriteInt(I);
|
||||
DataFlash.WriteInt(D);
|
||||
DataFlash.WriteInt(output);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
// Write a Radio packet
|
||||
void Log_Write_Radio(int ch1, int ch2, int ch3,int ch4, int ch5, int ch6)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_RADIO_MSG);
|
||||
DataFlash.WriteInt(ch1);
|
||||
DataFlash.WriteInt(ch2);
|
||||
DataFlash.WriteInt(ch3);
|
||||
DataFlash.WriteInt(ch4);
|
||||
DataFlash.WriteInt(ch5);
|
||||
DataFlash.WriteInt(ch6);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
#if LOG_PM
|
||||
// Write a performance monitoring packet. Total length : 19 bytes
|
||||
void Log_Write_Performance()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_PERFORMANCE_MSG);
|
||||
DataFlash.WriteLong(millis() - perf_mon_timer);
|
||||
DataFlash.WriteInt(mainLoop_count);
|
||||
DataFlash.WriteInt(G_Dt_max);
|
||||
DataFlash.WriteByte(gyro_sat_count);
|
||||
DataFlash.WriteByte(adc_constraints);
|
||||
DataFlash.WriteByte(renorm_sqrt_count);
|
||||
DataFlash.WriteByte(renorm_blowup_count);
|
||||
DataFlash.WriteByte(gps_fix_count);
|
||||
DataFlash.WriteInt((int)(imu_health*1000));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LOG_CTUN
|
||||
// Write a control tuning packet. Total length : 22 bytes
|
||||
void Log_Write_Control_Tuning()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_CONTROL_TUNING_MSG);
|
||||
DataFlash.WriteInt((int)(servo_out[CH_ROLL]*100));
|
||||
DataFlash.WriteInt((int)nav_roll);
|
||||
DataFlash.WriteInt((int)roll_sensor);
|
||||
DataFlash.WriteInt((int)(servo_out[CH_PITCH]*100));
|
||||
DataFlash.WriteInt((int)nav_pitch);
|
||||
DataFlash.WriteInt((int)pitch_sensor);
|
||||
DataFlash.WriteInt((int)(servo_out[CH_THROTTLE]*100));
|
||||
DataFlash.WriteInt((int)(servo_out[CH_RUDDER]*100));
|
||||
DataFlash.WriteInt((int)AN[5]);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LOG_NTUN
|
||||
// Write a navigation tuning packet. Total length : 18 bytes
|
||||
void Log_Write_Nav_Tuning()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_NAV_TUNING_MSG);
|
||||
DataFlash.WriteInt((int)yaw_sensor);
|
||||
DataFlash.WriteInt((int)wp_distance);
|
||||
DataFlash.WriteInt((int)target_bearing);
|
||||
DataFlash.WriteInt((int)nav_bearing);
|
||||
DataFlash.WriteInt(altitude_error);
|
||||
DataFlash.WriteInt((int)airspeed_error);
|
||||
DataFlash.WriteInt((int)(nav_gain_scaler*1000));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LOG_MODE
|
||||
// Write a mode packet. Total length : 5 bytes
|
||||
void Log_Write_Mode(byte mode)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_MODE_MSG);
|
||||
DataFlash.WriteByte(mode);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LOG_GPS
|
||||
// Write an GPS packet. Total length : 30 bytes
|
||||
void Log_Write_GPS( long log_Time, long log_Lattitude, long log_Longitude, long log_mix_alt, long log_gps_alt,
|
||||
long log_Ground_Speed, long log_Ground_Course, byte log_Fix, byte log_NumSats)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_GPS_MSG);
|
||||
DataFlash.WriteLong(log_Time);
|
||||
DataFlash.WriteByte(log_Fix);
|
||||
DataFlash.WriteByte(log_NumSats);
|
||||
DataFlash.WriteLong(log_Lattitude);
|
||||
DataFlash.WriteLong(log_Longitude);
|
||||
DataFlash.WriteLong(log_mix_alt);
|
||||
DataFlash.WriteLong(log_gps_alt);
|
||||
DataFlash.WriteLong(log_Ground_Speed);
|
||||
DataFlash.WriteLong(log_Ground_Course);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LOG_RAW
|
||||
// Write an raw accel/gyro data packet. Total length : 28 bytes
|
||||
void Log_Write_Raw()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_RAW_MSG);
|
||||
for(int i=0;i<6;i++)
|
||||
DataFlash.WriteLong((long)(AN[i]*1000.0));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LOG_RANGEFINDER
|
||||
// Write a Sensor Raw data packet
|
||||
void Log_Write_RangeFinder(int rf1, int rf2, int rf3,int rf4, int rf5, int rf6)
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_RANGEFINDER_MSG);
|
||||
DataFlash.WriteInt(rf1);
|
||||
DataFlash.WriteInt(rf2);
|
||||
DataFlash.WriteInt(rf3);
|
||||
DataFlash.WriteInt(rf4);
|
||||
DataFlash.WriteInt(rf5);
|
||||
DataFlash.WriteInt(rf6);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// Read an control tuning packet
|
||||
void Log_Read_Control_Tuning()
|
||||
{
|
||||
float logvar;
|
||||
|
||||
SerPri("CTUN:");
|
||||
for (int y=1;y<10;y++) {
|
||||
logvar = DataFlash.ReadInt();
|
||||
if(y < 9) logvar = logvar/100.f;
|
||||
SerPri(logvar);
|
||||
SerPri(",");
|
||||
}
|
||||
SerPriln(" ");
|
||||
}
|
||||
|
||||
// Read a nav tuning packet
|
||||
void Log_Read_Nav_Tuning()
|
||||
{
|
||||
float logvar;
|
||||
|
||||
SerPri("NTUN:");
|
||||
for (int y=1;y<8;y++) {
|
||||
logvar = DataFlash.ReadInt();
|
||||
if(y > 6) logvar = logvar/1000.f;
|
||||
SerPri(logvar);
|
||||
SerPri(",");
|
||||
}
|
||||
SerPriln(" ");
|
||||
}
|
||||
|
||||
// Read a performance packet
|
||||
void Log_Read_Performance()
|
||||
{
|
||||
long pm_time;
|
||||
int logvar;
|
||||
|
||||
SerPri("PM:");
|
||||
pm_time = DataFlash.ReadLong();
|
||||
SerPri(pm_time);
|
||||
SerPri(",");
|
||||
for (int y=1;y<9;y++) {
|
||||
if(y<3 || y>7) logvar = DataFlash.ReadInt();
|
||||
else logvar = DataFlash.ReadByte();
|
||||
if(y > 7) logvar = logvar/1000.f;
|
||||
SerPri(logvar);
|
||||
SerPri(",");
|
||||
}
|
||||
SerPriln(" ");
|
||||
}
|
||||
|
||||
// Read an attitude packet
|
||||
void Log_Read_Attitude()
|
||||
{
|
||||
int log_roll;
|
||||
int log_pitch;
|
||||
int log_yaw;
|
||||
|
||||
log_roll = DataFlash.ReadInt();
|
||||
log_pitch = DataFlash.ReadInt();
|
||||
log_yaw = DataFlash.ReadInt();
|
||||
SerPri("ATT:");
|
||||
SerPri(log_roll);
|
||||
SerPri(",");
|
||||
SerPri(log_pitch);
|
||||
SerPri(",");
|
||||
SerPri(log_yaw);
|
||||
SerPriln();
|
||||
}
|
||||
|
||||
// Read a Sensor packet
|
||||
void Log_Read_Sensor()
|
||||
{
|
||||
SerPri("SENSOR:");
|
||||
SerPri(DataFlash.ReadInt()); SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPriln();
|
||||
}
|
||||
|
||||
// Read a Sensor raw data packet
|
||||
void Log_Read_PID()
|
||||
{
|
||||
SerPri("PID:");
|
||||
SerPri((int)DataFlash.ReadByte()); // NUM_PID
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); // P
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); // I
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); // D
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt()); // output
|
||||
SerPriln();
|
||||
}
|
||||
|
||||
// Read an Radio packet
|
||||
void Log_Read_Radio()
|
||||
{
|
||||
SerPri("RADIO:");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPriln();
|
||||
}
|
||||
|
||||
// Read a mode packet
|
||||
void Log_Read_Mode()
|
||||
{
|
||||
byte mode;
|
||||
|
||||
mode = DataFlash.ReadByte();
|
||||
SerPri("MOD:");
|
||||
switch (mode) {
|
||||
case 0:
|
||||
SerPriln("Manual mode");
|
||||
break;
|
||||
case 1:
|
||||
SerPriln("Stabilize mode");
|
||||
break;
|
||||
case 5:
|
||||
SerPriln("Fly By Wire A mode");
|
||||
break;
|
||||
case 6:
|
||||
SerPriln("Fly By Wire B mode");
|
||||
break;
|
||||
case 10:
|
||||
SerPriln("AUTO mode");
|
||||
break;
|
||||
case 11:
|
||||
SerPriln("RTL mode");
|
||||
break;
|
||||
case 12:
|
||||
SerPriln("Loiter mode");
|
||||
break;
|
||||
case 98:
|
||||
SerPriln("Air Start Complete");
|
||||
break;
|
||||
case 99:
|
||||
SerPriln("Ground Start Complete");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Read a GPS packet
|
||||
void Log_Read_GPS()
|
||||
{
|
||||
long log_Time;
|
||||
byte log_Fix;
|
||||
byte log_NumSats;
|
||||
long log_Lattitude;
|
||||
long log_Longitude;
|
||||
long log_gps_alt;
|
||||
long log_mix_alt;
|
||||
float log_Ground_Speed;
|
||||
float log_Ground_Course;
|
||||
|
||||
log_Time = DataFlash.ReadLong();
|
||||
log_Fix = DataFlash.ReadByte();
|
||||
log_NumSats = DataFlash.ReadByte();
|
||||
log_Lattitude = DataFlash.ReadLong();
|
||||
log_Longitude = DataFlash.ReadLong();
|
||||
log_mix_alt = DataFlash.ReadLong();
|
||||
log_gps_alt = DataFlash.ReadLong();
|
||||
log_Ground_Speed = DataFlash.ReadLong();
|
||||
log_Ground_Course = DataFlash.ReadLong();
|
||||
|
||||
SerPri("GPS:");
|
||||
SerPri(log_Time);
|
||||
SerPri(",");
|
||||
SerPri((int)log_Fix);
|
||||
SerPri(",");
|
||||
SerPri((int)log_NumSats);
|
||||
SerPri(",");
|
||||
SerPri(log_Lattitude);
|
||||
SerPri(",");
|
||||
SerPri(log_Longitude);
|
||||
SerPri(",");
|
||||
SerPri(log_mix_alt/100.0);
|
||||
SerPri(",");
|
||||
SerPri(log_gps_alt/100.0);
|
||||
SerPri(",");
|
||||
SerPri(log_Ground_Speed/100.0f);
|
||||
SerPri(",");
|
||||
SerPri(log_Ground_Course/100.0); // This is incorrect!!!!!
|
||||
SerPriln();
|
||||
|
||||
}
|
||||
|
||||
// Read a raw accel/gyro packet
|
||||
void Log_Read_Raw()
|
||||
{
|
||||
float logvar;
|
||||
|
||||
SerPri("RAW:");
|
||||
for (int y=0;y<6;y++) {
|
||||
logvar = DataFlash.ReadLong()/1000.f;
|
||||
SerPri(logvar);
|
||||
SerPri(",");
|
||||
}
|
||||
SerPriln(" ");
|
||||
}
|
||||
|
||||
// Read a RangeFinder packet
|
||||
void Log_Read_RangeFinder()
|
||||
{
|
||||
SerPri("RF:");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPri(",");
|
||||
SerPri(DataFlash.ReadInt());
|
||||
SerPriln(" ");
|
||||
}
|
||||
|
||||
// Read the DataFlash log memory : Packet Parser
|
||||
void Log_Read(int start_page, int end_page)
|
||||
{
|
||||
byte data;
|
||||
byte log_step=0;
|
||||
int packet_count=0;
|
||||
int flash_led = 1;
|
||||
int numErrors = 0;
|
||||
|
||||
DataFlash.StartRead(start_page);
|
||||
while (DataFlash.GetPage() < end_page && numErrors < LOG_MAX_ERRORS)
|
||||
{
|
||||
data = DataFlash.ReadByte();
|
||||
switch(log_step) //This is a state machine to read the packets
|
||||
{
|
||||
case 0:
|
||||
if(data==HEAD_BYTE1) { // Head byte 1
|
||||
log_step++;
|
||||
numErrors = 0;
|
||||
}else
|
||||
numErrors++;
|
||||
break;
|
||||
case 1:
|
||||
if(data==HEAD_BYTE2) // Head byte 2
|
||||
log_step++;
|
||||
break;
|
||||
case 2:
|
||||
if(data==LOG_ATTITUDE_MSG){
|
||||
Log_Read_Attitude();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_GPS_MSG){
|
||||
Log_Read_GPS();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_MODE_MSG){
|
||||
Log_Read_Mode();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_CONTROL_TUNING_MSG){
|
||||
Log_Read_Control_Tuning();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_NAV_TUNING_MSG){
|
||||
Log_Read_Nav_Tuning();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_PERFORMANCE_MSG){
|
||||
Log_Read_Performance();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_RAW_MSG){
|
||||
Log_Read_Raw();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_RADIO_MSG){
|
||||
Log_Read_Radio();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_SENSOR_MSG){
|
||||
Log_Read_Sensor();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_PID_MSG){
|
||||
Log_Read_PID();
|
||||
log_step++;
|
||||
|
||||
}else if(data==LOG_RANGEFINDER_MSG) {
|
||||
Log_Read_RangeFinder();
|
||||
log_step++;
|
||||
|
||||
}else{
|
||||
SerPri("Error Reading Packet: ");
|
||||
SerPri(packet_count);
|
||||
log_step=0; // Restart, we have a problem...
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
if(data==END_BYTE){
|
||||
packet_count++;
|
||||
}else{
|
||||
SerPri("Error Reading END_BYTE ");
|
||||
SerPriln(data,DEC);
|
||||
}
|
||||
log_step=0; // Restart sequence: new packet...
|
||||
if(flash_led > 0) {
|
||||
digitalWrite(A_LED_PIN,HIGH);
|
||||
flash_led++;
|
||||
if(flash_led>100) flash_led=-1;
|
||||
} else {
|
||||
digitalWrite(A_LED_PIN,LOW);
|
||||
flash_led--;
|
||||
if(flash_led<-100) flash_led=1;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
SerPri("Number of packets read: ");
|
||||
SerPriln(packet_count);
|
||||
digitalWrite(A_LED_PIN,HIGH);
|
||||
}
|
||||
|
||||
|
@ -1,328 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Mixer.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
#ifdef USEMIXER
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
float MotorPitch[MAX_MOTORS];
|
||||
float MotorRoll[MAX_MOTORS];
|
||||
float MotorYaw[MAX_MOTORS];
|
||||
float MotorGas[MAX_MOTORS];
|
||||
float motorAxisCommandPitch[MAX_MOTORS];
|
||||
float motorAxisCommandRoll[MAX_MOTORS];
|
||||
float motorAxisCommandYaw[MAX_MOTORS];
|
||||
//float motorAxisCommand[3]; // Command on Roll YAW PITCH Recived from IMU
|
||||
|
||||
|
||||
#if FRAME_MODEL == QUAD
|
||||
// This is an example of QuadX configuration for mixertable
|
||||
void init_mixer_table()
|
||||
{
|
||||
// Example for Quad configuration
|
||||
MotorGas[0] = 100;
|
||||
MotorPitch[0] = -100;
|
||||
MotorRoll[0] = 100;
|
||||
MotorYaw[0] = 100;
|
||||
|
||||
MotorGas[1] = 100;
|
||||
MotorPitch[1] = 100;
|
||||
MotorRoll[1] = -100;
|
||||
MotorYaw[1] = 100;
|
||||
|
||||
MotorGas[2] = 100;
|
||||
MotorPitch[2] = -100;
|
||||
MotorRoll[2] = -100;
|
||||
MotorYaw[2] = -100;
|
||||
|
||||
MotorGas[3] = 100;
|
||||
MotorPitch[3] = 100;
|
||||
MotorRoll[3] = 100;
|
||||
MotorYaw[3] = -100;
|
||||
}
|
||||
|
||||
#elif FRAME_MODEL == HEXA
|
||||
void init_mixer_table()
|
||||
{
|
||||
// Hexa configuration
|
||||
MotorPitch[0] = -100;
|
||||
MotorRoll[0] = 0;
|
||||
MotorYaw[0] = 100;
|
||||
|
||||
MotorPitch[1] = -50;
|
||||
MotorRoll[1] = -100;
|
||||
MotorYaw[1] = -100;
|
||||
|
||||
MotorPitch[2] = +50;
|
||||
MotorRoll[2] = -100;
|
||||
MotorYaw[2] = 100;
|
||||
|
||||
MotorPitch[3] = +100;
|
||||
MotorRoll[3] = 0;
|
||||
MotorYaw[3] = -100;
|
||||
|
||||
|
||||
MotorPitch[4] = +50;
|
||||
MotorRoll[4] = 100;
|
||||
MotorYaw[4] = 100;
|
||||
|
||||
MotorPitch[5] = -50;
|
||||
MotorRoll[5] = 100;
|
||||
MotorYaw[5] = -100;
|
||||
}
|
||||
#elif FRAME_MODEL == HEXARADIAL
|
||||
void init_mixer_table()
|
||||
{
|
||||
// Example for Hexa configuration
|
||||
MotorGas[0] = 100;
|
||||
MotorPitch[0] = -100;
|
||||
MotorRoll[0] = 0;
|
||||
MotorYaw[0] = 100;
|
||||
|
||||
MotorGas[1] = 100;
|
||||
MotorPitch[1] = -50;
|
||||
MotorRoll[1] = -100;
|
||||
MotorYaw[1] = -100;
|
||||
|
||||
MotorGas[2] = 100;
|
||||
MotorPitch[2] = +50;
|
||||
MotorRoll[2] = -100;
|
||||
MotorYaw[2] = 100;
|
||||
|
||||
MotorGas[3] = 100;
|
||||
MotorPitch[3] = +100;
|
||||
MotorRoll[3] = 0;
|
||||
MotorYaw[3] = -100;
|
||||
|
||||
MotorGas[4] = 100;
|
||||
MotorPitch[4] = +50;
|
||||
MotorRoll[4] = 100;
|
||||
MotorYaw[4] = 100;
|
||||
|
||||
MotorGas[5] = 100;
|
||||
MotorPitch[5] = -50;
|
||||
MotorRoll[5] = 100;
|
||||
MotorYaw[5] = -100;
|
||||
}
|
||||
|
||||
#elif FRAME_MODEL == HEXACOAXIAL
|
||||
void init_mixer_table()
|
||||
{
|
||||
// Example for Hexa configuration
|
||||
MotorGas[0] = 95;
|
||||
MotorPitch[0] = 100;
|
||||
MotorRoll[0] = 0;
|
||||
MotorYaw[0] = 100;
|
||||
|
||||
MotorGas[1] = 100;
|
||||
MotorPitch[1] = 100;
|
||||
MotorRoll[1] = 0;
|
||||
MotorYaw[1] = -100;
|
||||
|
||||
MotorGas[2] = 95;
|
||||
MotorPitch[2] = -50;
|
||||
MotorRoll[2] = 100;
|
||||
MotorYaw[2] = -100;
|
||||
|
||||
MotorGas[3] = 100;
|
||||
MotorPitch[3] = -50;
|
||||
MotorRoll[3] = 100;
|
||||
MotorYaw[3] = 100;
|
||||
|
||||
MotorGas[4] = 95;
|
||||
MotorPitch[4] = -50;
|
||||
MotorRoll[4] = -100;
|
||||
MotorYaw[4] = -100;
|
||||
|
||||
MotorGas[5] = 100;
|
||||
MotorPitch[5] = -50;
|
||||
MotorRoll[5] = -100;
|
||||
MotorYaw[5] = 100;
|
||||
}
|
||||
|
||||
#elif FRAME_MODEL == OCTO
|
||||
void init_mixer_table()
|
||||
{
|
||||
// Octo configuration. Motors are numberd CW viewed from above starting at front = 1 (CW prop rotation)
|
||||
// Motor rotation is CCW for odd numbered motors
|
||||
MotorGas[0] = 100;
|
||||
MotorPitch[0] = 100;
|
||||
MotorRoll[0] = 0;
|
||||
MotorYaw[0] = -100;
|
||||
|
||||
MotorGas[1] = 100;
|
||||
MotorPitch[1] = 100;
|
||||
MotorRoll[1] = -100;
|
||||
MotorYaw[1] = 100;
|
||||
|
||||
MotorGas[2] = 100;
|
||||
MotorPitch[2] = 0;
|
||||
MotorRoll[2] = -100;
|
||||
MotorYaw[2] = -100;
|
||||
|
||||
MotorGas[3] = 100;
|
||||
MotorPitch[3] = -100;
|
||||
MotorRoll[3] = -100;
|
||||
MotorYaw[3] = 100;
|
||||
|
||||
MotorGas[4] = 100;
|
||||
MotorPitch[4] = -100;
|
||||
MotorRoll[4] = 0;
|
||||
MotorYaw[4] = -100;
|
||||
|
||||
MotorGas[5] = 100;
|
||||
MotorPitch[5] = -100;
|
||||
MotorRoll[5] = 100;
|
||||
MotorYaw[5] = 100;
|
||||
|
||||
MotorGas[6] = 100;
|
||||
MotorPitch[6] = 0;
|
||||
MotorRoll[6] = 100;
|
||||
MotorYaw[6] = -100;
|
||||
|
||||
MotorGas[7] = 100;
|
||||
MotorPitch[7] = 100;
|
||||
MotorRoll[7] = 100;
|
||||
MotorYaw[7] = 100;
|
||||
}
|
||||
#else
|
||||
# error You need define your frame configuration on ArduUser.h
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
void motor_axis_correction()
|
||||
{
|
||||
int i;
|
||||
for (i=0;i<MAX_MOTORS;i++)
|
||||
{
|
||||
motorAxisCommandPitch[i] = (control_pitch / 100.0) * MotorPitch[i];
|
||||
motorAxisCommandRoll[i] = (control_roll / 100.0) * MotorRoll[i];
|
||||
motorAxisCommandYaw[i] = (control_yaw / 100.0) * MotorYaw[i];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//After that we can mix them together:
|
||||
void motor_matrix_command()
|
||||
{
|
||||
int i;
|
||||
float valuemotor;
|
||||
for (i=0;i<MAX_MOTORS;i++)
|
||||
{
|
||||
valuemotor = ((ch_throttle* MotorGas[i])/100) + motorAxisCommandPitch[i] + motorAxisCommandYaw[i] + motorAxisCommandRoll[i];
|
||||
//valuemotor = Throttle + motorAxisCommandPitch[i] + motorAxisCommandYaw[i] + motorAxisCommandRoll[i]; // OLD VERSION WITHOUT GAS CONOL ON Mixertable
|
||||
valuemotor = constrain(valuemotor, 1000, 2000);
|
||||
motorCommand[i]=valuemotor;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void matrix_debug()
|
||||
{
|
||||
|
||||
Serial.println();
|
||||
Serial.println("--------------------------");
|
||||
Serial.println(" Motori Mixertable " );
|
||||
Serial.println("--------------------------");
|
||||
Serial.println();
|
||||
Serial.println("--------------------------");
|
||||
Serial.println(" Quad Motor Debug " );
|
||||
Serial.println("--------------------------");
|
||||
|
||||
Serial.print("AIL:");
|
||||
Serial.print(ch_roll);
|
||||
Serial.print(" ELE:");
|
||||
Serial.print(ch_pitch);
|
||||
Serial.print(" THR:");
|
||||
Serial.print( ch_throttle);
|
||||
Serial.print(" YAW:");
|
||||
Serial.print( ch_yaw);
|
||||
Serial.print(" AUX:");
|
||||
Serial.print(ch_aux);
|
||||
Serial.print(" AUX2:");
|
||||
Serial.print(ch_aux2);
|
||||
Serial.println();
|
||||
Serial.print("CONTROL_ROLL:");
|
||||
Serial.print(control_roll);
|
||||
Serial.print(" CONTROL_PITCH:");
|
||||
Serial.print(control_pitch);
|
||||
Serial.print(" CONTROL_YAW:");
|
||||
Serial.print(control_yaw);
|
||||
Serial.print(" SONAR_VALUE:");
|
||||
// Serial.print(sonar_value);
|
||||
// Serial.print(" TARGET_SONAR_VALUE:");
|
||||
// Serial.print(target_sonar_altitude);
|
||||
// Serial.print(" ERR_SONAR_VALUE:");
|
||||
// Serial.print(err_altitude);
|
||||
// Serial.println();
|
||||
// Serial.print("latitude:");
|
||||
// Serial.print(GPS_np.Lattitude);
|
||||
// Serial.print(" longitude:");
|
||||
// Serial.print(GPS_np.Longitude);
|
||||
Serial.print(" command gps roll:");
|
||||
Serial.print(command_gps_roll);
|
||||
Serial.print(" command gps pitch:");
|
||||
Serial.print(command_gps_pitch);
|
||||
// Serial.print(" Lon_diff:");
|
||||
// Serial.print(Lon_diff);
|
||||
// Serial.print(" Lon_diff");
|
||||
// Serial.print(command_gps_pitch);
|
||||
Serial.println();
|
||||
Serial.print("AP MODE:");
|
||||
Serial.print((int)AP_mode);
|
||||
Serial.println();
|
||||
|
||||
#ifdef HEXARADIAL
|
||||
Serial.println();
|
||||
Serial.print((unsigned int)MotorI2C[5]);
|
||||
comma();
|
||||
Serial.print((unsigned int)MotorI2C[0]);
|
||||
comma();
|
||||
Serial.print((unsigned int)MotorI2C[1]);
|
||||
comma();
|
||||
Serial.println();
|
||||
Serial.print((unsigned int)MotorI2C[4]);
|
||||
comma();
|
||||
Serial.print((unsigned int)MotorI2C[3]);
|
||||
comma();
|
||||
Serial.println((unsigned int)MotorI2C[2]);
|
||||
Serial.println("---------------");
|
||||
Serial.println();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
#endif // usemixer
|
@ -1,106 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Motors.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
|
||||
|
||||
// Send output commands to ESC´s
|
||||
void motor_output()
|
||||
{
|
||||
int throttle;
|
||||
byte throttle_mode=0;
|
||||
|
||||
throttle = ch_throttle;
|
||||
#if (defined(UseBMP) || defined(IsSONAR))
|
||||
if (AP_mode == AP_AUTOMATIC_MODE)
|
||||
{
|
||||
throttle = ch_throttle_altitude_hold;
|
||||
throttle_mode=1;
|
||||
}
|
||||
#endif
|
||||
|
||||
if ((throttle_mode==0)&&(ch_throttle < (MIN_THROTTLE + 100))) // If throttle is low we disable yaw (neccesary to arm/disarm motors safely)
|
||||
control_yaw = 0;
|
||||
|
||||
// Quadcopter mix
|
||||
if (motorArmed == 1) {
|
||||
#ifdef IsAM
|
||||
digitalWrite(FR_LED, HIGH); // AM-Mode
|
||||
#endif
|
||||
|
||||
// Quadcopter output mix
|
||||
rightMotor = constrain(throttle - control_roll + control_yaw, minThrottle, 2000);
|
||||
leftMotor = constrain(throttle + control_roll + control_yaw, minThrottle, 2000);
|
||||
frontMotor = constrain(throttle + control_pitch - control_yaw, minThrottle, 2000);
|
||||
backMotor = constrain(throttle - control_pitch - control_yaw, minThrottle, 2000);
|
||||
|
||||
} else { // MOTORS DISARMED
|
||||
|
||||
#ifdef IsAM
|
||||
digitalWrite(FR_LED, LOW); // AM-Mode
|
||||
#endif
|
||||
digitalWrite(LED_Green,HIGH); // Ready LED on
|
||||
|
||||
rightMotor = MIN_THROTTLE;
|
||||
leftMotor = MIN_THROTTLE;
|
||||
frontMotor = MIN_THROTTLE;
|
||||
backMotor = MIN_THROTTLE;
|
||||
|
||||
// Reset_I_Terms();
|
||||
roll_I = 0; // reset I terms of PID controls
|
||||
pitch_I = 0;
|
||||
yaw_I = 0;
|
||||
|
||||
// Initialize yaw command to actual yaw when throttle is down...
|
||||
command_rx_yaw = ToDeg(yaw);
|
||||
}
|
||||
|
||||
//#if MOTORTYPE == PWM
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(0, rightMotor);
|
||||
APM_RC.OutputCh(1, leftMotor);
|
||||
APM_RC.OutputCh(2, frontMotor);
|
||||
APM_RC.OutputCh(3, backMotor);
|
||||
|
||||
// InstantPWM => Force inmediate output on PWM signals
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
//#elif MOTORTYPE == I2C
|
||||
|
||||
//#else
|
||||
//# error You need to define your motor type on ArduUder.pde file
|
||||
//#endif
|
||||
}
|
||||
|
||||
|
@ -1,279 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Navigation.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
- initial functions.
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
void read_GPS_data()
|
||||
{
|
||||
#ifdef IsGPS
|
||||
GPS_timer_old=GPS_timer; // Update GPS timer
|
||||
GPS_timer = millis();
|
||||
GPS_Dt = (GPS_timer-GPS_timer_old)*0.001; // GPS_Dt
|
||||
GPS.NewData=0; // We Reset the flag...
|
||||
|
||||
// Write GPS data to DataFlash log
|
||||
Log_Write_GPS(GPS.Time, GPS.Lattitude, GPS.Longitude, GPS.Altitude, GPS.Altitude, GPS.Ground_Speed, GPS.Ground_Course, GPS.Fix, GPS.NumSats);
|
||||
|
||||
//if (GPS.Fix >= 2)
|
||||
if (GPS.Fix)
|
||||
digitalWrite(LED_Red,HIGH); // GPS Fix => RED LED
|
||||
else
|
||||
digitalWrite(LED_Red,LOW);
|
||||
#endif
|
||||
}
|
||||
|
||||
/* GPS based Position control */
|
||||
void Position_control(long lat_dest, long lon_dest)
|
||||
{
|
||||
#ifdef IsGPS
|
||||
long Lon_diff;
|
||||
long Lat_diff;
|
||||
|
||||
Lon_diff = lon_dest - GPS.Longitude;
|
||||
Lat_diff = lat_dest - GPS.Lattitude;
|
||||
|
||||
//If we have not calculated GEOG_CORRECTION_FACTOR we calculate it here as cos(lattitude)
|
||||
if (GEOG_CORRECTION_FACTOR==0)
|
||||
GEOG_CORRECTION_FACTOR = cos(ToRad(GPS.Lattitude/10000000.0));
|
||||
|
||||
// ROLL
|
||||
//Optimization : cos(yaw) = DCM_Matrix[0][0] ; sin(yaw) = DCM_Matrix[1][0] [This simplification is valid for low roll angles]
|
||||
gps_err_roll = (float)Lon_diff * GEOG_CORRECTION_FACTOR * DCM_Matrix[0][0] - (float)Lat_diff * DCM_Matrix[1][0];
|
||||
|
||||
gps_roll_D = (gps_err_roll-gps_err_roll_old) / GPS_Dt;
|
||||
gps_err_roll_old = gps_err_roll;
|
||||
|
||||
gps_roll_I += gps_err_roll * GPS_Dt;
|
||||
gps_roll_I = constrain(gps_roll_I, -800, 800);
|
||||
|
||||
command_gps_roll = KP_GPS_ROLL * gps_err_roll + KD_GPS_ROLL * gps_roll_D + KI_GPS_ROLL * gps_roll_I;
|
||||
command_gps_roll = constrain(command_gps_roll, -GPS_MAX_ANGLE, GPS_MAX_ANGLE); // Limit max command
|
||||
|
||||
//Log_Write_PID(1,KP_GPS_ROLL*gps_err_roll*10,KI_GPS_ROLL*gps_roll_I*10,KD_GPS_ROLL*gps_roll_D*10,command_gps_roll*10);
|
||||
|
||||
// PITCH
|
||||
gps_err_pitch = -(float)Lat_diff * DCM_Matrix[0][0] - (float)Lon_diff * GEOG_CORRECTION_FACTOR * DCM_Matrix[1][0];
|
||||
|
||||
gps_pitch_D = (gps_err_pitch - gps_err_pitch_old) / GPS_Dt;
|
||||
gps_err_pitch_old = gps_err_pitch;
|
||||
|
||||
gps_pitch_I += gps_err_pitch * GPS_Dt;
|
||||
gps_pitch_I = constrain(gps_pitch_I, -800, 800);
|
||||
|
||||
command_gps_pitch = KP_GPS_PITCH * gps_err_pitch + KD_GPS_PITCH * gps_pitch_D + KI_GPS_PITCH * gps_pitch_I;
|
||||
command_gps_pitch = constrain(command_gps_pitch, -GPS_MAX_ANGLE, GPS_MAX_ANGLE); // Limit max command
|
||||
|
||||
//Log_Write_PID(2,KP_GPS_PITCH*gps_err_pitch*10,KI_GPS_PITCH*gps_pitch_I*10,KD_GPS_PITCH*gps_pitch_D*10,command_gps_pitch*10);
|
||||
#endif
|
||||
}
|
||||
|
||||
/* GPS based Position control Version 2 - builds up I and D term using lat/lon instead of roll/pitch*/
|
||||
void Position_control_v2(long lat_dest, long lon_dest)
|
||||
{
|
||||
#ifdef IsGPS
|
||||
//If we have not calculated GEOG_CORRECTION_FACTOR we calculate it here as cos(lattitude)
|
||||
if (GEOG_CORRECTION_FACTOR==0)
|
||||
GEOG_CORRECTION_FACTOR = cos(ToRad(GPS.Lattitude/10000000.0));
|
||||
|
||||
// store old lat & lon diff for d term?
|
||||
gps_err_lon_old = gps_err_lon;
|
||||
gps_err_lat_old = gps_err_lat;
|
||||
|
||||
// calculate distance from target - for P term
|
||||
gps_err_lon = (float)(lon_dest - GPS.Longitude) * GEOG_CORRECTION_FACTOR;
|
||||
gps_err_lat = lat_dest - GPS.Lattitude;
|
||||
|
||||
// add distance to I term
|
||||
gps_lon_I += gps_err_lon;
|
||||
gps_lon_I = constrain(gps_lon_I,-1200,1200); // don't let I get too big
|
||||
gps_lat_I += gps_err_lat;
|
||||
gps_lat_I = constrain(gps_lat_I,-1200,1200);
|
||||
|
||||
// calculate the ground speed - for D term
|
||||
gps_lon_D = (gps_err_lon - gps_err_lon_old) / GPS_Dt;
|
||||
gps_lat_D = (gps_err_lat - gps_err_lat_old) / GPS_Dt;
|
||||
|
||||
// Now separate lat & lon PID terms into roll & pitch components
|
||||
// ROLL
|
||||
//Optimization : cos(yaw) = DCM_Matrix[0][0] ; sin(yaw) = DCM_Matrix[1][0] [This simplification is valid for low roll angles]
|
||||
gps_err_roll = (gps_err_lon * DCM_Matrix[0][0] - gps_err_lat * DCM_Matrix[1][0]);
|
||||
gps_roll_I = (gps_lon_I * DCM_Matrix[0][0] - gps_lat_I * DCM_Matrix[1][0]);
|
||||
gps_roll_D = (gps_lon_D * DCM_Matrix[0][0] - gps_lat_D * DCM_Matrix[1][0]);
|
||||
|
||||
command_gps_roll = KP_GPS_ROLL * gps_err_roll + KD_GPS_ROLL * gps_roll_D + KI_GPS_ROLL * gps_roll_I;
|
||||
command_gps_roll = constrain(command_gps_roll, -GPS_MAX_ANGLE, GPS_MAX_ANGLE); // Limit max command
|
||||
Log_Write_PID(1,KP_GPS_ROLL*gps_err_roll,KI_GPS_ROLL*gps_roll_I,KD_GPS_ROLL*gps_roll_D,command_gps_roll);
|
||||
|
||||
// PITCH
|
||||
gps_err_pitch = (-gps_err_lat * DCM_Matrix[0][0] - gps_err_lon * DCM_Matrix[1][0]);
|
||||
gps_pitch_I = (-gps_lat_I * DCM_Matrix[0][0] - gps_lon_I * DCM_Matrix[1][0]);
|
||||
gps_pitch_D = (-gps_lat_D * DCM_Matrix[0][0] - gps_lon_D * DCM_Matrix[1][0]);
|
||||
|
||||
command_gps_pitch = KP_GPS_PITCH * gps_err_pitch + KD_GPS_PITCH * gps_pitch_D + KI_GPS_PITCH * gps_pitch_I;
|
||||
command_gps_pitch = constrain(command_gps_pitch, -GPS_MAX_ANGLE, GPS_MAX_ANGLE); // Limit max command
|
||||
Log_Write_PID(2,KP_GPS_PITCH*gps_err_pitch,KI_GPS_PITCH*gps_pitch_I,KD_GPS_PITCH*gps_pitch_D,command_gps_pitch);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
void Reset_I_terms_navigation()
|
||||
{
|
||||
gps_roll_I = 0;
|
||||
gps_pitch_I = 0;
|
||||
gps_lon_I = 0; // for position hold ver 2
|
||||
gps_lat_I = 0;
|
||||
}
|
||||
|
||||
/* ************************************************************ */
|
||||
/* Altitude control... (based on barometer) */
|
||||
int Altitude_control_baro(int altitude, int target_altitude)
|
||||
{
|
||||
#define ALTITUDE_CONTROL_BARO_OUTPUT_MIN 40
|
||||
#define ALTITUDE_CONTROL_BARO_OUTPUT_MAX 80
|
||||
|
||||
// !!!!! REMOVE THIS !!!!!!!
|
||||
#define KP_BARO_ALTITUDE 0.25 //0.3
|
||||
#define KD_BARO_ALTITUDE 0.09 //0.09
|
||||
#define KI_BARO_ALTITUDE 0.1
|
||||
|
||||
int command_altitude;
|
||||
|
||||
err_altitude_old = err_altitude;
|
||||
err_altitude = target_altitude - altitude;
|
||||
baro_altitude_I += (float)err_altitude*0.05;
|
||||
baro_altitude_I = constrain(baro_altitude_I,-140,140);
|
||||
baro_altitude_D = (float)(err_altitude-err_altitude_old)/0.05; // 20Hz
|
||||
command_altitude = KP_ALTITUDE*err_altitude + KD_ALTITUDE*baro_altitude_D + KI_ALTITUDE*baro_altitude_I;
|
||||
command_altitude = initial_throttle + constrain(command_altitude,-ALTITUDE_CONTROL_BARO_OUTPUT_MIN,ALTITUDE_CONTROL_BARO_OUTPUT_MAX);
|
||||
Log_Write_PID(5,KP_ALTITUDE*err_altitude,KI_ALTITUDE*baro_altitude_I,KD_ALTITUDE*baro_altitude_D,command_altitude);
|
||||
return command_altitude;
|
||||
}
|
||||
|
||||
/* ************************************************************ */
|
||||
/* Altitude control... (based on sonar) */
|
||||
#define GdT_SONAR_ALTITUDE 0.05
|
||||
#define ALTITUDE_CONTROL_SONAR_OUTPUT_MIN 60
|
||||
#define ALTITUDE_CONTROL_SONAR_OUTPUT_MAX 80
|
||||
int Altitude_control_Sonar(int altitude, int target_altitude)
|
||||
{
|
||||
static int err_altitude = 0;
|
||||
int command_altitude;
|
||||
int err_altitude_old;
|
||||
|
||||
err_altitude_old = err_altitude;
|
||||
err_altitude = target_altitude - altitude;
|
||||
sonar_altitude_I += (float)err_altitude*GdT_SONAR_ALTITUDE;
|
||||
sonar_altitude_I = constrain(sonar_altitude_I,-1000,1000);
|
||||
sonar_altitude_D = (float)(err_altitude-err_altitude_old)/GdT_SONAR_ALTITUDE;
|
||||
command_altitude = KP_SONAR_ALTITUDE*err_altitude + KI_SONAR_ALTITUDE*sonar_altitude_I + KD_SONAR_ALTITUDE*sonar_altitude_D ;
|
||||
command_altitude = initial_throttle + constrain(command_altitude,-ALTITUDE_CONTROL_SONAR_OUTPUT_MIN,ALTITUDE_CONTROL_SONAR_OUTPUT_MAX);
|
||||
Log_Write_PID(4,KP_SONAR_ALTITUDE*err_altitude,KI_SONAR_ALTITUDE*sonar_altitude_I,KD_SONAR_ALTITUDE*sonar_altitude_D,command_altitude);
|
||||
return command_altitude;
|
||||
}
|
||||
|
||||
/* ************************************************************ */
|
||||
/* Obstacle avoidance routine */
|
||||
#ifdef IsRANGEFINDER
|
||||
void Obstacle_avoidance(int safeDistance)
|
||||
{
|
||||
int RF_err_roll = 0;
|
||||
int RF_err_pitch = 0;
|
||||
int RF_err_throttle = 0;
|
||||
float RF_roll_P;
|
||||
float RF_roll_D;
|
||||
float RF_pitch_P;
|
||||
float RF_pitch_D;
|
||||
float RF_throttle_P;
|
||||
float RF_throttle_D;
|
||||
static int RF_err_roll_old;
|
||||
static int RF_err_pitch_old;
|
||||
static int RF_err_throttle_old;
|
||||
int err_temp;
|
||||
|
||||
// front right
|
||||
err_temp = max(safeDistance - AP_RangeFinder_frontRight.distance,0);
|
||||
RF_err_roll += err_temp * AP_RangeFinder_frontRight.orientation_x;
|
||||
RF_err_pitch += err_temp * AP_RangeFinder_frontRight.orientation_y;
|
||||
RF_err_throttle += err_temp * AP_RangeFinder_frontRight.orientation_z;
|
||||
|
||||
// back right
|
||||
err_temp = max(safeDistance - AP_RangeFinder_backRight.distance,0);
|
||||
RF_err_roll += err_temp * AP_RangeFinder_backRight.orientation_x;
|
||||
RF_err_pitch += err_temp * AP_RangeFinder_backRight.orientation_y;
|
||||
RF_err_throttle += err_temp * AP_RangeFinder_backRight.orientation_z;
|
||||
|
||||
// back left
|
||||
err_temp = max(safeDistance - AP_RangeFinder_backLeft.distance,0);
|
||||
RF_err_roll += err_temp * AP_RangeFinder_backLeft.orientation_x;
|
||||
RF_err_pitch += err_temp * AP_RangeFinder_backLeft.orientation_y;
|
||||
RF_err_throttle += err_temp * AP_RangeFinder_backLeft.orientation_z;
|
||||
|
||||
// front left
|
||||
err_temp = max(safeDistance - AP_RangeFinder_frontLeft.distance,0);
|
||||
RF_err_roll += err_temp * AP_RangeFinder_frontLeft.orientation_x;
|
||||
RF_err_pitch += err_temp * AP_RangeFinder_frontLeft.orientation_y;
|
||||
RF_err_throttle += err_temp * AP_RangeFinder_frontLeft.orientation_z;
|
||||
|
||||
// ROLL - P term
|
||||
RF_roll_P = RF_err_roll * KP_RF_ROLL;
|
||||
RF_roll_P = constrain(RF_roll_P,-RF_MAX_ANGLE,RF_MAX_ANGLE);
|
||||
// ROLL - I term
|
||||
RF_roll_I += RF_err_roll * 0.05 * KI_RF_ROLL;
|
||||
RF_roll_I = constrain(RF_roll_I,-RF_MAX_ANGLE/2,RF_MAX_ANGLE/2);
|
||||
// ROLL - D term
|
||||
RF_roll_D = (RF_err_roll-RF_err_roll_old) / 0.05 * KD_RF_ROLL; // RF_IR frequency is 20Hz (50ms)
|
||||
RF_roll_D = constrain(RF_roll_D,-RF_MAX_ANGLE/2,RF_MAX_ANGLE/2);
|
||||
RF_err_roll_old = RF_err_roll;
|
||||
// ROLL - full comand
|
||||
command_RF_roll = RF_roll_P + RF_roll_I + RF_roll_D;
|
||||
command_RF_roll = constrain(command_RF_roll,-RF_MAX_ANGLE,RF_MAX_ANGLE); // Limit max command
|
||||
|
||||
// PITCH - P term
|
||||
RF_pitch_P = RF_err_pitch * KP_RF_PITCH;
|
||||
RF_pitch_P = constrain(RF_pitch_P,-RF_MAX_ANGLE,RF_MAX_ANGLE);
|
||||
// PITCH - I term
|
||||
RF_pitch_I += RF_err_pitch * 0.05 * KI_RF_PITCH;
|
||||
RF_pitch_I = constrain(RF_pitch_I,-RF_MAX_ANGLE/2,RF_MAX_ANGLE/2);
|
||||
// PITCH - D term
|
||||
RF_pitch_D = (RF_err_pitch-RF_err_pitch_old) / 0.05 * KD_RF_PITCH; // RF_IR frequency is 20Hz (50ms)
|
||||
RF_pitch_D = constrain(RF_pitch_D,-RF_MAX_ANGLE/2,RF_MAX_ANGLE/2);
|
||||
RF_err_pitch_old = RF_err_pitch;
|
||||
// PITCH - full comand
|
||||
command_RF_pitch = RF_pitch_P + RF_pitch_I + RF_pitch_D;
|
||||
command_RF_pitch = constrain(command_RF_pitch,-RF_MAX_ANGLE,RF_MAX_ANGLE); // Limit max command
|
||||
|
||||
// THROTTLE - not yet implemented
|
||||
command_RF_throttle = 0;
|
||||
}
|
||||
#endif
|
||||
|
@ -1,12 +0,0 @@
|
||||
Greetings to all,
|
||||
|
||||
This is our net architectural layout for ArduCopter main code. It is
|
||||
work-on-progress code and currently does not work.
|
||||
|
||||
So please do not use this code from ArducopterNG folder. After code is
|
||||
working properly, it will be moved to Arducopter folder.
|
||||
|
||||
We try to hammer it out as soon as possible...
|
||||
|
||||
Best regards,
|
||||
ArduCopter TEAM
|
@ -1,156 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Radio.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
#define STICK_TO_ANGLE_FACTOR 12.0 // To convert stick position to absolute angles
|
||||
#define YAW_STICK_TO_ANGLE_FACTOR 150.0
|
||||
|
||||
void read_radio()
|
||||
{
|
||||
int tempThrottle = 0;
|
||||
|
||||
// Commands from radio Rx
|
||||
// We apply the Radio calibration parameters (from configurator) except for throttle
|
||||
ch_roll = channel_filter(APM_RC.InputCh(CH_ROLL) * ch_roll_slope + ch_roll_offset, ch_roll);
|
||||
ch_pitch = channel_filter(APM_RC.InputCh(CH_PITCH) * ch_pitch_slope + ch_pitch_offset, ch_pitch);
|
||||
ch_yaw = channel_filter(APM_RC.InputCh(CH_RUDDER) * ch_yaw_slope + ch_yaw_offset, ch_yaw);
|
||||
ch_aux = APM_RC.InputCh(CH_5) * ch_aux_slope + ch_aux_offset;
|
||||
ch_aux2 = APM_RC.InputCh(CH_6) * ch_aux2_slope + ch_aux2_offset;
|
||||
|
||||
// special checks for throttle
|
||||
tempThrottle = APM_RC.InputCh(CH_THROTTLE);
|
||||
|
||||
// throttle safety check
|
||||
if( motorSafety == 1 ) {
|
||||
if( motorArmed == 1 ) {
|
||||
if( ch_throttle > MIN_THROTTLE + 100 ) { // if throttle is now over MIN..
|
||||
// if throttle has increased suddenly, disarm motors
|
||||
if( (tempThrottle - ch_throttle) > SAFETY_MAX_THROTTLE_INCREASE ) {
|
||||
motorArmed = 0;
|
||||
}else{ // if it hasn't increased too quickly turn off the safety
|
||||
motorSafety = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}else if( ch_throttle < MIN_THROTTLE + 100 ) { // Safety logic: hold throttle low for more than 1 second, safety comes on which stops sudden increases in throttle
|
||||
Safety_counter++;
|
||||
if( Safety_counter > SAFETY_DELAY ) {
|
||||
motorSafety = 1;
|
||||
Safety_counter = 0;
|
||||
}
|
||||
}else{ // throttle is over MIN so make sure to reset Safety_counter
|
||||
Safety_counter = 0;
|
||||
}
|
||||
// normal throttle filtering. Note: Transmiter calibration not used on throttle
|
||||
ch_throttle = channel_filter(tempThrottle, ch_throttle);
|
||||
|
||||
// Flight mode
|
||||
if(ch_aux2 > 1300)
|
||||
flightMode = ACRO_MODE; // Force to Acro mode from radio
|
||||
else
|
||||
flightMode = STABLE_MODE; // Stable mode (default)
|
||||
|
||||
// Autopilot mode (only works on Stable mode)
|
||||
if (flightMode == STABLE_MODE)
|
||||
{
|
||||
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
|
||||
}
|
||||
|
||||
if (flightMode==STABLE_MODE) // IN STABLE MODE we convert stick positions to absoulte angles
|
||||
{
|
||||
// In Stable mode stick position defines the desired angle in roll, pitch and yaw
|
||||
// #ifdef FLIGHT_MODE_X
|
||||
if(flightOrientation) {
|
||||
// For X mode we make a mix in the input
|
||||
float aux_roll = (ch_roll-roll_mid) / STICK_TO_ANGLE_FACTOR;
|
||||
float aux_pitch = (ch_pitch-pitch_mid) / STICK_TO_ANGLE_FACTOR;
|
||||
command_rx_roll = aux_roll - aux_pitch;
|
||||
command_rx_pitch = aux_roll + aux_pitch;
|
||||
} else {
|
||||
command_rx_roll = (ch_roll-roll_mid) / STICK_TO_ANGLE_FACTOR; // Convert stick position to absolute angles
|
||||
command_rx_pitch = (ch_pitch-pitch_mid) / STICK_TO_ANGLE_FACTOR;
|
||||
}
|
||||
|
||||
// YAW
|
||||
if (abs(ch_yaw-yaw_mid)>6) // Take into account a bit of "dead zone" on yaw
|
||||
{
|
||||
command_rx_yaw += (ch_yaw-yaw_mid) / YAW_STICK_TO_ANGLE_FACTOR;
|
||||
command_rx_yaw = Normalize_angle(command_rx_yaw); // Normalize angle to [-180,180]
|
||||
}
|
||||
}
|
||||
|
||||
// Write Radio data to DataFlash log
|
||||
Log_Write_Radio(ch_roll,ch_pitch,ch_throttle,ch_yaw,ch_aux,ch_aux2);
|
||||
|
||||
// Motor arm logic
|
||||
if (ch_throttle < (MIN_THROTTLE + 100)) {
|
||||
control_yaw = 0;
|
||||
command_rx_yaw = ToDeg(yaw);
|
||||
|
||||
// Arm motor output : Throttle down and full yaw right for more than 2 seconds
|
||||
if (ch_yaw > 1850) {
|
||||
if (Arming_counter > ARM_DELAY){
|
||||
if(ch_throttle > 800) {
|
||||
motorArmed = 1;
|
||||
minThrottle = MIN_THROTTLE+60; // A minimun value for mantain a bit if throttle
|
||||
}
|
||||
}
|
||||
else
|
||||
Arming_counter++;
|
||||
}
|
||||
else
|
||||
Arming_counter=0;
|
||||
|
||||
// To Disarm motor output : Throttle down and full yaw left for more than 2 seconds
|
||||
if (ch_yaw < 1150) {
|
||||
if (Disarming_counter > DISARM_DELAY){
|
||||
motorArmed = 0;
|
||||
minThrottle = MIN_THROTTLE;
|
||||
}
|
||||
else
|
||||
Disarming_counter++;
|
||||
}
|
||||
else
|
||||
Disarming_counter=0;
|
||||
}
|
||||
else{
|
||||
Arming_counter=0;
|
||||
Disarming_counter=0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,153 +0,0 @@
|
||||
/*
|
||||
www.ArduCopter.com - www.DIYDrones.com
|
||||
Copyright (c) 2010. All rights reserved.
|
||||
An Open Source Arduino based multicopter.
|
||||
|
||||
File : Sensors.pde
|
||||
Version : v1.0, Aug 27, 2010
|
||||
Author(s): ArduCopter Team
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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/>.
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
/* ******* ADC functions ********************* */
|
||||
// Read all the ADC channles
|
||||
void Read_adc_raw(void)
|
||||
{
|
||||
//int temp;
|
||||
|
||||
for (int i=0;i<6;i++)
|
||||
AN[i] = adc.Ch(sensors[i]);
|
||||
}
|
||||
|
||||
// Returns an analog value with the offset
|
||||
int read_adc(int select)
|
||||
{
|
||||
if (SENSOR_SIGN[select]<0)
|
||||
return (AN_OFFSET[select]-AN[select]);
|
||||
else
|
||||
return (AN[select]-AN_OFFSET[select]);
|
||||
}
|
||||
|
||||
void calibrateSensors(void) {
|
||||
int i;
|
||||
int j = 0;
|
||||
byte gyro;
|
||||
float aux_float[3];
|
||||
|
||||
Read_adc_raw(); // Read sensors data
|
||||
delay(5);
|
||||
|
||||
// Offset values for accels and gyros...
|
||||
AN_OFFSET[3] = acc_offset_x; // Accel offset values are taken from external calibration (In Configurator)
|
||||
AN_OFFSET[4] = acc_offset_y;
|
||||
AN_OFFSET[5] = acc_offset_z;
|
||||
aux_float[0] = gyro_offset_roll;
|
||||
aux_float[1] = gyro_offset_pitch;
|
||||
aux_float[2] = gyro_offset_yaw;
|
||||
|
||||
// Take the gyro offset values
|
||||
for(i=0;i<600;i++)
|
||||
{
|
||||
Read_adc_raw(); // Read sensors
|
||||
for(gyro = GYROZ; gyro <= GYROY; gyro++)
|
||||
aux_float[gyro] = aux_float[gyro] * 0.8 + AN[gyro] * 0.2; // Filtering
|
||||
Log_Write_Sensor(AN[0], AN[1], AN[2], AN[3], AN[4], AN[5], 0);
|
||||
|
||||
delay(5);
|
||||
|
||||
RunningLights(j); // (in Functions.pde)
|
||||
// Runnings lights effect to let user know that we are taking mesurements
|
||||
if((i % 5) == 0) j++;
|
||||
if(j >= 3) j = 0;
|
||||
}
|
||||
|
||||
// Switch off all ABC lights
|
||||
LightsOff();
|
||||
|
||||
for(gyro = GYROZ; gyro <= GYROY; gyro++)
|
||||
AN_OFFSET[gyro] = aux_float[gyro]; // Update sensor OFFSETs from values read
|
||||
}
|
||||
|
||||
#ifdef UseBMP
|
||||
void read_baro(void)
|
||||
{
|
||||
float tempPresAlt;
|
||||
|
||||
tempPresAlt = float(APM_BMP085.Press)/101325.0;
|
||||
//tempPresAlt = pow(tempPresAlt, 0.190284);
|
||||
//press_alt = (1.0 - tempPresAlt) * 145366.45;
|
||||
tempPresAlt = pow(tempPresAlt, 0.190295);
|
||||
if (press_baro_altitude == 0)
|
||||
press_baro_altitude = (1.0 - tempPresAlt) * 4433000; // Altitude in cm
|
||||
else
|
||||
press_baro_altitude = press_baro_altitude * 0.75 + ((1.0 - tempPresAlt) * 4433000)*0.25; // Altitude in cm (filtered)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef IsSONAR
|
||||
/* This function reads in the values from the attached range finders (currently only downward pointing sonar) */
|
||||
void read_Sonar()
|
||||
{
|
||||
// calculate altitude from down sensor
|
||||
AP_RangeFinder_down.read();
|
||||
|
||||
// translate into an altitude
|
||||
press_sonar_altitude = DCM_Matrix[2][2] * AP_RangeFinder_down.distance;
|
||||
|
||||
// deal with the unusual case that we're up-side-down
|
||||
if( press_sonar_altitude < 0 )
|
||||
press_sonar_altitude = 0;
|
||||
|
||||
// set sonar status to OK and update sonar_valid_count which shows reliability of sonar (i.e. are we out of range?)
|
||||
if( AP_RangeFinder_down.distance > sonar_threshold ) {
|
||||
sonar_status = SONAR_STATUS_BAD;
|
||||
if( sonar_valid_count > 0 )
|
||||
sonar_valid_count = -1;
|
||||
else
|
||||
sonar_valid_count--;
|
||||
}else{
|
||||
sonar_status = SONAR_STATUS_OK;
|
||||
if( sonar_valid_count < 0 )
|
||||
sonar_valid_count = 1;
|
||||
else
|
||||
sonar_valid_count++;
|
||||
}
|
||||
sonar_valid_count = constrain(sonar_valid_count,-10,10);
|
||||
|
||||
#if LOG_RANGEFINDER && !defined(IsRANGEFINDER)
|
||||
Log_Write_RangeFinder(AP_RangeFinder_down.distance,0,0,0,0,0);
|
||||
#endif
|
||||
}
|
||||
#endif // IsSONAR
|
||||
|
||||
#ifdef IsRANGEFINDER
|
||||
/* This function reads in the values from the attached range finders (currently only downward pointing sonar) */
|
||||
void read_RF_Sensors()
|
||||
{
|
||||
AP_RangeFinder_frontRight.read();
|
||||
AP_RangeFinder_backRight.read();
|
||||
AP_RangeFinder_backLeft.read();
|
||||
AP_RangeFinder_frontLeft.read();
|
||||
|
||||
#if LOG_RANGEFINDER
|
||||
Log_Write_RangeFinder(AP_RangeFinder_down.distance, AP_RangeFinder_frontRight.distance, AP_RangeFinder_backRight.distance, AP_RangeFinder_backLeft.distance,AP_RangeFinder_frontLeft.distance,0);
|
||||
#endif
|
||||
}
|
||||
#endif // IsRANGEFINDER
|
||||
|
@ -1,218 +0,0 @@
|
||||
/*
|
||||
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
|
||||
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
||||
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
||||
Sandro Benigno, Chris Anderson
|
||||
|
||||
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:
|
||||
|
||||
|
||||
* ************************************************************** *
|
||||
TODO:
|
||||
|
||||
|
||||
* ************************************************************** */
|
||||
|
||||
// General Initialization for all APM electronics
|
||||
void APM_Init() {
|
||||
|
||||
// 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)
|
||||
|
||||
// Because DDRE and DDRL Ports are not included to normal Arduino Libraries, we need to
|
||||
// initialize them with a special command
|
||||
APMPinMode(DDRE,7,INPUT); // DIP1, (PE7), Closest DIP to sliding SW2 switch
|
||||
APMPinMode(DDRE,6,INPUT); // DIP2, (PE6)
|
||||
APMPinMode(DDRL,6,INPUT); // DIP3, (PL6)
|
||||
APMPinMode(DDRL,7,INPUT); // DIP4, (PL7), Furthest DIP from sliding SW2 switch
|
||||
|
||||
|
||||
/* ********************************************************* */
|
||||
/////////////////////////////////////////////////////////
|
||||
// Normal Initialization sequence starts from here.
|
||||
readUserConfig(); // Load user configurable items from EEPROM
|
||||
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
#if AIRFRAME == QUAD
|
||||
// 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);
|
||||
#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
|
||||
// Make sure that Relay is switched off.
|
||||
digitalWrite(RELAY,LOW);
|
||||
|
||||
// Wiggle LEDs while ESCs are rebooting
|
||||
FullBlink(50,20);
|
||||
|
||||
adc.Init(); // APM ADC library initialization
|
||||
DataFlash.Init(); // DataFlash log initialization
|
||||
|
||||
#ifdef IsGPS
|
||||
GPS.Init(); // GPS Initialization
|
||||
|
||||
#ifdef IsNEWMTEK
|
||||
delay(250);
|
||||
|
||||
// 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
|
||||
Serial1.print("$PMTK220,200*2C\r\n"); // 5Hz update rate
|
||||
delay(200);
|
||||
Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n");
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// 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);
|
||||
|
||||
// Is CLI mode active or not, if it is fire it up and never return.
|
||||
if(!digitalRead(SW2)) {
|
||||
RunCLI();
|
||||
// Btw.. We never return from this....
|
||||
}
|
||||
|
||||
|
||||
flightOrientation = SW_DIP1; // DIP1 off = we are in + mode, DIP1 on = we are in x mode
|
||||
|
||||
// readUserConfig moved to up to ensure min throttle is read from eeprom
|
||||
//readUserConfig(); // Load user configurable items from EEPROM
|
||||
|
||||
// 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;
|
||||
|
||||
#if AIRFRAME == QUAD
|
||||
// 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);
|
||||
#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
|
||||
|
||||
// Initialise Wire library used by Magnetometer and Barometer
|
||||
Wire.begin();
|
||||
|
||||
#ifdef IsMAG
|
||||
if (MAGNETOMETER == 1) {
|
||||
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));
|
||||
}
|
||||
#endif
|
||||
|
||||
DataFlash.StartWrite(1); // Start a write session on page 1
|
||||
|
||||
// Proper Serial port/baud are defined on main .pde and then Arducopter.h with
|
||||
// Choises of Xbee or normal serial port
|
||||
SerBeg(SerBau);
|
||||
|
||||
// Check if we enable the DataFlash log Read Mode (switch)
|
||||
// If we press switch 1 at startup we read the Dataflash eeprom
|
||||
while (digitalRead(SW1)==0) // LEGACY remove soon by jp, 30-10-10
|
||||
{
|
||||
Serial.println("Entering Log Read Mode..."); // This will be obsole soon due moving to CLI system
|
||||
Log_Read(1,1000);
|
||||
delay(30000);
|
||||
}
|
||||
|
||||
calibrateSensors(); // Calibrate neutral values of gyros (in Sensors.pde)
|
||||
|
||||
// Neutro_yaw = APM_RC.InputCh(3); // Take yaw neutral radio value
|
||||
#ifndef CONFIGURATOR
|
||||
for(i=0;i<6;i++)
|
||||
{
|
||||
SerPri("AN[]:");
|
||||
SerPrln(AN_OFFSET[i]);
|
||||
}
|
||||
SerPri("Yaw neutral value:");
|
||||
SerPri(yaw_mid);
|
||||
#endif
|
||||
|
||||
#ifdef UseBMP
|
||||
APM_BMP085.Init(FALSE);
|
||||
#endif
|
||||
|
||||
// Sonar for Altitude hold
|
||||
#ifdef IsSONAR
|
||||
AP_RangeFinder_down.init(AP_RANGEFINDER_PITOT_TUBE, &adc); AP_RangeFinder_down.set_orientation(AP_RANGEFINDER_ORIENTATION_DOWN);
|
||||
//AP_RangeFinder_down.init(AN5); AP_RangeFinder_down.set_orientation(AP_RANGEFINDER_ORIENTATION_DOWN);
|
||||
sonar_threshold = AP_RangeFinder_down.max_distance * 0.8;
|
||||
sonar_status = SONAR_STATUS_OK; // assume sonar is ok to start with
|
||||
#endif
|
||||
|
||||
// RangeFinders for obstacle avoidance
|
||||
#ifdef IsRANGEFINDER
|
||||
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);
|
||||
#endif
|
||||
|
||||
delay(1000);
|
||||
|
||||
DataFlash.StartWrite(1); // Start a write session on page 1
|
||||
|
||||
// initialise helicopter
|
||||
#if AIRFRAME == HELI
|
||||
heli_setup();
|
||||
#endif
|
||||
|
||||
#ifdef IsAM
|
||||
// Switch Left & Right lights on
|
||||
digitalWrite(RI_LED, HIGH);
|
||||
digitalWrite(LE_LED, HIGH);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
@ -1,2 +0,0 @@
|
||||
[My Computer]
|
||||
My Computer = "localhost"
|
@ -1,15 +0,0 @@
|
||||
[AeroQuadConfigurator]
|
||||
server.app.propertiesEnabled = False
|
||||
server.ole.enabled = False
|
||||
server.tcp.serviceName = "My Computer/VI Server"
|
||||
server.vi.propertiesEnabled = False
|
||||
WebServer.TcpAccess = "c+*"
|
||||
WebServer.ViAccess = "+*"
|
||||
DebugServerEnabled = False
|
||||
DebugServerWaitOnLaunch = False
|
||||
useLocaleDecimalPt = False
|
||||
|
||||
[Configuration]
|
||||
COMport = "COM13"
|
||||
Timeout = 10
|
||||
Baud = 115200
|
@ -1,15 +0,0 @@
|
||||
[AeroQuadConfigurator]
|
||||
server.app.propertiesEnabled = False
|
||||
server.ole.enabled = False
|
||||
server.tcp.serviceName = "My Computer/VI Server"
|
||||
server.vi.propertiesEnabled = False
|
||||
WebServer.TcpAccess = "c+*"
|
||||
WebServer.ViAccess = "+*"
|
||||
DebugServerEnabled = False
|
||||
DebugServerWaitOnLaunch = False
|
||||
useLocaleDecimalPt = False
|
||||
|
||||
[Configuration]
|
||||
COMport = "COM13"
|
||||
Timeout = 10
|
||||
Baud = 115200
|
@ -1,327 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="3.5" DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<PropertyGroup>
|
||||
<Configuration Condition=" '$(Configuration)' == '' ">Debug</Configuration>
|
||||
<Platform Condition=" '$(Platform)' == '' ">AnyCPU</Platform>
|
||||
<ProductVersion>9.0.30729</ProductVersion>
|
||||
<SchemaVersion>2.0</SchemaVersion>
|
||||
<ProjectGuid>{AF26391C-7E45-4401-8984-96139A67FF31}</ProjectGuid>
|
||||
<OutputType>WinExe</OutputType>
|
||||
<AppDesignerFolder>Properties</AppDesignerFolder>
|
||||
<RootNamespace>ArducopterConfigurator</RootNamespace>
|
||||
<AssemblyName>ArducopterConfigurator</AssemblyName>
|
||||
<TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
<IsWebBootstrapper>true</IsWebBootstrapper>
|
||||
<ManifestCertificateThumbprint>AEF4CA248129E2377F0B2723CB7C9BA864483D54</ManifestCertificateThumbprint>
|
||||
<ManifestKeyFile>configuratorCert.pfx</ManifestKeyFile>
|
||||
<GenerateManifests>true</GenerateManifests>
|
||||
<SignManifests>false</SignManifests>
|
||||
<PublishUrl>publish\</PublishUrl>
|
||||
<Install>true</Install>
|
||||
<InstallFrom>Web</InstallFrom>
|
||||
<UpdateEnabled>true</UpdateEnabled>
|
||||
<UpdateMode>Background</UpdateMode>
|
||||
<UpdateInterval>7</UpdateInterval>
|
||||
<UpdateIntervalUnits>Days</UpdateIntervalUnits>
|
||||
<UpdatePeriodically>false</UpdatePeriodically>
|
||||
<UpdateRequired>false</UpdateRequired>
|
||||
<MapFileExtensions>true</MapFileExtensions>
|
||||
<InstallUrl>http://mandrolic.com/configurator/</InstallUrl>
|
||||
<ProductName>Arducopter Configurator</ProductName>
|
||||
<PublisherName>Andrew Radford</PublisherName>
|
||||
<CreateWebPageOnPublish>true</CreateWebPageOnPublish>
|
||||
<WebPage>index.htm</WebPage>
|
||||
<OpenBrowserOnPublish>false</OpenBrowserOnPublish>
|
||||
<ApplicationRevision>11</ApplicationRevision>
|
||||
<ApplicationVersion>1.0.0.%2a</ApplicationVersion>
|
||||
<UseApplicationTrust>false</UseApplicationTrust>
|
||||
<PublishWizardCompleted>true</PublishWizardCompleted>
|
||||
<BootstrapperEnabled>true</BootstrapperEnabled>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Debug|AnyCPU' ">
|
||||
<DebugSymbols>true</DebugSymbols>
|
||||
<DebugType>full</DebugType>
|
||||
<Optimize>false</Optimize>
|
||||
<OutputPath>bin\Debug\</OutputPath>
|
||||
<DefineConstants>DEBUG;TRACE</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|AnyCPU' ">
|
||||
<DebugType>pdbonly</DebugType>
|
||||
<Optimize>true</Optimize>
|
||||
<OutputPath>bin\Release\</OutputPath>
|
||||
<DefineConstants>TRACE</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
</PropertyGroup>
|
||||
<ItemGroup>
|
||||
<Reference Include="System" />
|
||||
<Reference Include="System.Data" />
|
||||
<Reference Include="System.Deployment" />
|
||||
<Reference Include="System.Drawing" />
|
||||
<Reference Include="System.Windows.Forms" />
|
||||
<Reference Include="System.Xml" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Compile Include="CommsSession.cs">
|
||||
</Compile>
|
||||
<Compile Include="FakeCommsSession.cs" />
|
||||
<Compile Include="PresentationModels\AcroModeConfigVm.cs" />
|
||||
<Compile Include="PresentationModels\AltitudeHoldConfigVm.cs" />
|
||||
<Compile Include="PresentationModels\ConfigWithPidsBase.cs" />
|
||||
<Compile Include="Core\DelegateCommand.cs" />
|
||||
<Compile Include="PresentationModels\GPSstatusVm.cs" />
|
||||
<Compile Include="PresentationModels\CrudVm.cs" />
|
||||
<Compile Include="PresentationModels\DoubleVm.cs" />
|
||||
<Compile Include="PresentationModels\PositionAltitudePidsVm.cs" />
|
||||
<Compile Include="PresentationModels\FlightControlPidsVm.cs" />
|
||||
<Compile Include="PresentationModels\ItalksToApm.cs" />
|
||||
<Compile Include="PresentationModels\MainVm.cs" />
|
||||
<Compile Include="PresentationModels\SensorsVm.cs" />
|
||||
<Compile Include="PresentationModels\VmBase.cs" />
|
||||
<Compile Include="Views\controls\CircularIndicatorControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\CircularIndicatorControl.Designer.cs">
|
||||
<DependentUpon>CircularIndicatorControl.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\CompassControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\CompassControl.Designer.cs">
|
||||
<DependentUpon>CompassControl.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\PropControl.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\PropControl.Designer.cs">
|
||||
<DependentUpon>PropControl.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\QuadPlanControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\QuadPlanControl.Designer.cs">
|
||||
<DependentUpon>QuadPlanControl.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\LinearIndicatorControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\controls\LinearIndicatorControl.Designer.cs">
|
||||
<DependentUpon>LinearIndicatorControl.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\GpsView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\GpsView.Designer.cs">
|
||||
<DependentUpon>GpsView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\PositionAltitudePidsView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\PositionAltitudePidsView.Designer.cs">
|
||||
<DependentUpon>PositionAltitudePidsView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\FlightControlPidsView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\FlightControlPidsView.Designer.cs">
|
||||
<DependentUpon>FlightControlPidsView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\mainForm.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\mainForm.Designer.cs">
|
||||
<DependentUpon>mainForm.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="NotifyProperyChangedBase.cs" />
|
||||
<Compile Include="PresentationModels\MotorCommandsVm.cs" />
|
||||
<Compile Include="PresentationModels\PositionHoldConfigVm.cs" />
|
||||
<Compile Include="PresentationModels\StableModeConfigVm.cs" />
|
||||
<Compile Include="PresentationModels\TransmitterChannelsVm.cs" />
|
||||
<Compile Include="Program.cs" />
|
||||
<Compile Include="Properties\AssemblyInfo.cs" />
|
||||
<EmbeddedResource Include="Views\mainForm.resx">
|
||||
<DependentUpon>mainForm.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Properties\Resources.resx">
|
||||
<Generator>ResXFileCodeGenerator</Generator>
|
||||
<LastGenOutput>Resources.Designer.cs</LastGenOutput>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\AcroConfigView.resx">
|
||||
<DependentUpon>AcroConfigView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\AltitudeHoldConfigView.resx">
|
||||
<DependentUpon>AltitudeHoldConfigView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\PositionHoldConfigView.resx">
|
||||
<DependentUpon>PositionHoldConfigView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\StableConfigView.resx">
|
||||
<DependentUpon>StableConfigView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\FlightDataView.resx">
|
||||
<DependentUpon>FlightDataView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\MotorCommandsView.resx">
|
||||
<DependentUpon>MotorCommandsView.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\SerialMonitorView.resx">
|
||||
<DependentUpon>SerialMonitorView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\TransmitterChannelsView.resx">
|
||||
<DependentUpon>TransmitterChannelsView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<Compile Include="Properties\Resources.Designer.cs">
|
||||
<AutoGen>True</AutoGen>
|
||||
<DependentUpon>Resources.resx</DependentUpon>
|
||||
</Compile>
|
||||
<None Include="configuratorCert.pfx" />
|
||||
<None Include="Properties\DataSources\ArducopterConfigurator.PresentationModels.AcroModeConfigVm.datasource" />
|
||||
<None Include="Properties\DataSources\ArducopterConfigurator.PresentationModels.FlightDataVm.datasource" />
|
||||
<None Include="Properties\DataSources\ArducopterConfigurator.PresentationModels.MainVm.datasource" />
|
||||
<None Include="Properties\DataSources\ArducopterConfigurator.PresentationModels.StableModeConfigVm.datasource" />
|
||||
<None Include="Properties\DataSources\SerialMonitorVm.datasource" />
|
||||
<None Include="Properties\Settings.settings">
|
||||
<Generator>SettingsSingleFileGenerator</Generator>
|
||||
<LastGenOutput>Settings.Designer.cs</LastGenOutput>
|
||||
</None>
|
||||
<Compile Include="Properties\Settings.Designer.cs">
|
||||
<AutoGen>True</AutoGen>
|
||||
<DependentUpon>Settings.settings</DependentUpon>
|
||||
<DesignTimeSharedInput>True</DesignTimeSharedInput>
|
||||
</Compile>
|
||||
<Compile Include="Views\AcroConfigView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\AcroConfigView.Designer.cs">
|
||||
<DependentUpon>AcroConfigView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\AltitudeHoldConfigView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\AltitudeHoldConfigView.Designer.cs">
|
||||
<DependentUpon>AltitudeHoldConfigView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Core\IPresentationModel.cs" />
|
||||
<Compile Include="Core\IView.cs" />
|
||||
<Compile Include="Views\PositionHoldConfigView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\PositionHoldConfigView.Designer.cs">
|
||||
<DependentUpon>PositionHoldConfigView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\StableConfigView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\StableConfigView.Designer.cs">
|
||||
<DependentUpon>StableConfigView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\FlightDataView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\FlightDataView.Designer.cs">
|
||||
<DependentUpon>FlightDataView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\MotorCommandsView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\MotorCommandsView.Designer.cs">
|
||||
<DependentUpon>MotorCommandsView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\SerialMonitorView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\SerialMonitorView.Designer.cs">
|
||||
<DependentUpon>SerialMonitorView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="PresentationModels\SerialMonitorVm.cs" />
|
||||
<Compile Include="Views\TransmitterChannelsView.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Views\TransmitterChannelsView.Designer.cs">
|
||||
<DependentUpon>TransmitterChannelsView.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Views\ViewCommon.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<EmbeddedResource Include="Views\controls\CircularIndicatorControl.resx">
|
||||
<DependentUpon>CircularIndicatorControl.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\controls\CompassControl.resx">
|
||||
<DependentUpon>CompassControl.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\controls\PropControl.resx">
|
||||
<DependentUpon>PropControl.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\controls\QuadPlanControl.resx">
|
||||
<DependentUpon>QuadPlanControl.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\GpsView.resx">
|
||||
<DependentUpon>GpsView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\PositionAltitudePidsView.resx">
|
||||
<DependentUpon>PositionAltitudePidsView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\FlightControlPidsView.resx">
|
||||
<DependentUpon>FlightControlPidsView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Views\icons\refresh.ico" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Content Include="Readme.txt" />
|
||||
<Content Include="Views\icons\arrow_up.png" />
|
||||
<Content Include="Views\icons\chip.gif" />
|
||||
<Content Include="Views\icons\connect.ico" />
|
||||
<Content Include="Views\icons\disconnect.ico" />
|
||||
<Content Include="Views\icons\install.png" />
|
||||
<Content Include="Views\icons\Misc-Tools.ico" />
|
||||
<Content Include="Views\icons\saveIcon.png" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Client.3.5">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework Client Profile</ProductName>
|
||||
<Install>false</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Framework.2.0">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework 2.0 %28x86%29</ProductName>
|
||||
<Install>false</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Framework.3.0">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework 3.0 %28x86%29</ProductName>
|
||||
<Install>false</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Framework.3.5">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework 3.5</ProductName>
|
||||
<Install>false</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Net.Framework.3.5.SP1">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>.NET Framework 3.5 SP1</ProductName>
|
||||
<Install>true</Install>
|
||||
</BootstrapperPackage>
|
||||
<BootstrapperPackage Include="Microsoft.Windows.Installer.3.1">
|
||||
<Visible>False</Visible>
|
||||
<ProductName>Windows Installer 3.1</ProductName>
|
||||
<Install>true</Install>
|
||||
</BootstrapperPackage>
|
||||
</ItemGroup>
|
||||
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
|
||||
<Import Project="$(MSBuildBinPath)\Microsoft.CSharp.targets" />
|
||||
<!-- To modify your build process, add your task inside one of the targets below and uncomment it.
|
||||
Other similar extension points exist, see Microsoft.Common.targets.
|
||||
<Target Name="BeforeBuild">
|
||||
</Target>
|
||||
<Target Name="AfterBuild">
|
||||
</Target>
|
||||
-->
|
||||
</Project>
|
@ -1,26 +0,0 @@
|
||||
|
||||
Microsoft Visual Studio Solution File, Format Version 10.00
|
||||
# Visual Studio 2008
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArducopterConfigurator", "ArducopterConfigurator.csproj", "{AF26391C-7E45-4401-8984-96139A67FF31}"
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArducopterConfiguratorTest", "Test\ArducopterConfiguratorTest.csproj", "{36B62E9F-668C-45BF-AD72-CFF0C0A65898}"
|
||||
EndProject
|
||||
Global
|
||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||
Debug|Any CPU = Debug|Any CPU
|
||||
Release|Any CPU = Release|Any CPU
|
||||
EndGlobalSection
|
||||
GlobalSection(ProjectConfigurationPlatforms) = postSolution
|
||||
{AF26391C-7E45-4401-8984-96139A67FF31}.Debug|Any CPU.ActiveCfg = Debug|Any CPU
|
||||
{AF26391C-7E45-4401-8984-96139A67FF31}.Debug|Any CPU.Build.0 = Debug|Any CPU
|
||||
{AF26391C-7E45-4401-8984-96139A67FF31}.Release|Any CPU.ActiveCfg = Release|Any CPU
|
||||
{AF26391C-7E45-4401-8984-96139A67FF31}.Release|Any CPU.Build.0 = Release|Any CPU
|
||||
{36B62E9F-668C-45BF-AD72-CFF0C0A65898}.Debug|Any CPU.ActiveCfg = Debug|Any CPU
|
||||
{36B62E9F-668C-45BF-AD72-CFF0C0A65898}.Debug|Any CPU.Build.0 = Debug|Any CPU
|
||||
{36B62E9F-668C-45BF-AD72-CFF0C0A65898}.Release|Any CPU.ActiveCfg = Release|Any CPU
|
||||
{36B62E9F-668C-45BF-AD72-CFF0C0A65898}.Release|Any CPU.Build.0 = Release|Any CPU
|
||||
EndGlobalSection
|
||||
GlobalSection(SolutionProperties) = preSolution
|
||||
HideSolutionNode = FALSE
|
||||
EndGlobalSection
|
||||
EndGlobal
|
@ -1,144 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.IO.Ports;
|
||||
using System.Text;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public interface IComms
|
||||
{
|
||||
event Action<string> LineOfDataReceived;
|
||||
string CommPort { get; set; }
|
||||
bool IsConnected { get; }
|
||||
int BaudRate { get; set; }
|
||||
IEnumerable<string> ListCommPorts();
|
||||
void Send(string send);
|
||||
bool Connect();
|
||||
bool DisConnect();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Represents a session of communication with the Arducopter
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// Looks after connection state etc
|
||||
/// </remarks>
|
||||
public class CommsSession : IComms
|
||||
{
|
||||
private readonly SerialPort _sp;
|
||||
private BackgroundWorker _bgWorker;
|
||||
|
||||
public event Action<string> LineOfDataReceived;
|
||||
|
||||
public CommsSession()
|
||||
{
|
||||
_sp = new SerialPort();
|
||||
}
|
||||
|
||||
public string CommPort { get; set; }
|
||||
|
||||
public int BaudRate { get; set; }
|
||||
|
||||
public bool Connect()
|
||||
{
|
||||
_sp.BaudRate = BaudRate;
|
||||
_sp.PortName = CommPort;
|
||||
_sp.NewLine = "\n";
|
||||
_sp.Handshake = Handshake.None;
|
||||
|
||||
try
|
||||
{
|
||||
_sp.Open();
|
||||
_sp.ReadTimeout = 50000;
|
||||
|
||||
|
||||
// start the reading BG thread
|
||||
_bgWorker = new BackgroundWorker();
|
||||
_bgWorker.DoWork += bgWorker_DoWork;
|
||||
_bgWorker.WorkerReportsProgress = true;
|
||||
_bgWorker.WorkerSupportsCancellation = true;
|
||||
_bgWorker.ProgressChanged += bgWorker_ProgressChanged;
|
||||
_bgWorker.RunWorkerAsync();
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
Error = ex.Message;
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
|
||||
public bool DisConnect()
|
||||
{
|
||||
_bgWorker.CancelAsync();
|
||||
|
||||
_sp.Close();
|
||||
return true;
|
||||
}
|
||||
|
||||
void bgWorker_ProgressChanged(object sender, ProgressChangedEventArgs e)
|
||||
{
|
||||
// Thanks to BG worker, this should be raised on the UI thread
|
||||
var lineReceived = e.UserState as string;
|
||||
|
||||
// TODO: POSSIBLE MONO ISSUE
|
||||
// Weird thing happening with the serial port on mono; sometimes the first
|
||||
// char is nulled. Work around for now is to drop it, and just send the remaining
|
||||
// chars up the stack. This is of course exteremely bogus
|
||||
if (lineReceived[0] == 0)
|
||||
{
|
||||
Console.WriteLine("Warning - received null first character. Dropping.");
|
||||
lineReceived = lineReceived.Substring(1);
|
||||
}
|
||||
|
||||
//Console.WriteLine("Processing Update: " + lineReceived);
|
||||
|
||||
if (LineOfDataReceived != null)
|
||||
LineOfDataReceived(lineReceived);
|
||||
}
|
||||
|
||||
void bgWorker_DoWork(object sender, DoWorkEventArgs e)
|
||||
{
|
||||
while (!_bgWorker.CancellationPending)
|
||||
{
|
||||
try
|
||||
{
|
||||
var line = _sp.ReadLine();
|
||||
_bgWorker.ReportProgress(0, line);
|
||||
}
|
||||
catch(TimeoutException)
|
||||
{
|
||||
// continue
|
||||
}
|
||||
catch(System.IO.IOException) // when the port gets killed
|
||||
{}
|
||||
catch(ObjectDisposedException)
|
||||
{}
|
||||
}
|
||||
}
|
||||
|
||||
private string Error { get; set;}
|
||||
|
||||
|
||||
public bool IsConnected
|
||||
{
|
||||
get { return _sp.IsOpen; }
|
||||
}
|
||||
|
||||
|
||||
|
||||
public IEnumerable<string> ListCommPorts()
|
||||
{
|
||||
return SerialPort.GetPortNames();
|
||||
}
|
||||
|
||||
public void Send(string send)
|
||||
{
|
||||
if (_sp.IsOpen)
|
||||
_sp.Write(send);
|
||||
}
|
||||
}
|
||||
}
|
@ -1,41 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public interface ICommand
|
||||
{
|
||||
void Execute(object parameter);
|
||||
bool CanExecute(object parameter);
|
||||
}
|
||||
|
||||
public class DelegateCommand : ICommand
|
||||
{
|
||||
private readonly Predicate<object> _canExecute;
|
||||
private readonly Action<object> _execute;
|
||||
|
||||
public DelegateCommand(Action<object> execute)
|
||||
: this(execute, null)
|
||||
{
|
||||
}
|
||||
|
||||
public DelegateCommand(Action<object> execute, Predicate<object> canExecute)
|
||||
{
|
||||
_execute = execute;
|
||||
_canExecute = canExecute;
|
||||
}
|
||||
|
||||
public bool CanExecute(object parameter)
|
||||
{
|
||||
if (_canExecute == null)
|
||||
return true;
|
||||
|
||||
return _canExecute(parameter);
|
||||
}
|
||||
|
||||
public void Execute(object parameter)
|
||||
{
|
||||
_execute(parameter);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
@ -1,13 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public interface IPresentationModel : ItalksToApm
|
||||
{
|
||||
string Name { get; }
|
||||
void Activate();
|
||||
void DeActivate();
|
||||
|
||||
event EventHandler updatedByApm;
|
||||
}
|
||||
}
|
@ -1,10 +0,0 @@
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public interface IView<Tmodel> where Tmodel : IPresentationModel
|
||||
{
|
||||
void SetDataContext(Tmodel vm);
|
||||
Control Control { get; }
|
||||
}
|
||||
}
|
@ -1,132 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
/// <summary>
|
||||
/// Fake implementation of Comms + APM for testing without a device connected
|
||||
/// </summary>
|
||||
public class FakeCommsSession : IComms
|
||||
{
|
||||
private bool _connected;
|
||||
private string _jabberData;
|
||||
private readonly Timer _jabberTimer;
|
||||
|
||||
#region Implementation of IComms
|
||||
|
||||
public FakeCommsSession()
|
||||
{
|
||||
_jabberTimer = new Timer();
|
||||
_jabberTimer.Interval = 1000;
|
||||
_jabberTimer.Tick += timer_Tick;
|
||||
}
|
||||
|
||||
public event Action<string> LineOfDataReceived;
|
||||
|
||||
public string CommPort { get; set; }
|
||||
|
||||
public bool IsConnected
|
||||
{
|
||||
get { return _connected; }
|
||||
}
|
||||
|
||||
public int BaudRate { get; set; }
|
||||
|
||||
|
||||
public IEnumerable<string> ListCommPorts()
|
||||
{
|
||||
return new[] {"FakePort1", "FakePort2"};
|
||||
}
|
||||
|
||||
public void Send(string stringSent)
|
||||
{
|
||||
if (!_connected)
|
||||
throw new InvalidOperationException("Not Connected");
|
||||
|
||||
if (stringSent == "!")
|
||||
ReturnData("Fake");
|
||||
|
||||
if (stringSent == "D") // position
|
||||
ReturnData("0.015,0.005,0.010,0.015,0.005,0.010,22.000,0.870");
|
||||
if (stringSent == "B") // stable
|
||||
ReturnData("1.950,0.100,0.200,1.950,0.300,0.400,3.200,0.500,0.600,0.320,1.00");
|
||||
if (stringSent == "P") // acro
|
||||
ReturnData("3.950,0.100,0.000,0.000,0.300,0.400,3.200,0.500,0.600,0.320");
|
||||
if (stringSent == "F") // alti
|
||||
ReturnData("0.800,0.200,0.300");
|
||||
if (stringSent == "J") // calib
|
||||
ReturnData("0.100,0.200,0.300,0.400,0.500,0.600");
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
if (stringSent == "S")
|
||||
{
|
||||
// Loop Time = 2
|
||||
// Roll Gyro Rate = -10
|
||||
// Pitch Gyro Rate = 3
|
||||
// Yaw Gyro Rate = -2
|
||||
// Throttle Output = 1011
|
||||
// Roll PID Output = 1012
|
||||
// Pitch PID Output = 1002
|
||||
// Yaw PID Output 1000
|
||||
// Front Motor Command = 1001 PWM output sent to right motor (ranges from 1000-2000)
|
||||
// Rear Motor Command 1003
|
||||
// Right Motor Command = 1002
|
||||
// Left Motor Command = 1004
|
||||
// then adc 4,3, and 5
|
||||
// mag heading float * 3
|
||||
// mag heading int * 3
|
||||
|
||||
_jabberData = "2,-10,3,-2,1011,1012,1002,1000,1001,1200,1003,1400,1000,1000,1000,1.000,1.000,1.000,0,0,0";
|
||||
StartJabber();
|
||||
}
|
||||
if (stringSent == "X")
|
||||
StopJabber();
|
||||
}
|
||||
|
||||
private void StopJabber()
|
||||
{
|
||||
_jabberTimer.Stop();
|
||||
}
|
||||
|
||||
private void StartJabber()
|
||||
{
|
||||
_jabberTimer.Start();
|
||||
}
|
||||
|
||||
void timer_Tick(object sender, EventArgs e)
|
||||
{
|
||||
ReturnData(_jabberData);
|
||||
}
|
||||
|
||||
|
||||
private void ReturnData(string data)
|
||||
{
|
||||
if (LineOfDataReceived != null)
|
||||
LineOfDataReceived(data + "\n");
|
||||
}
|
||||
|
||||
public bool Connect()
|
||||
{
|
||||
if (_connected)
|
||||
throw new InvalidOperationException("Already Connected");
|
||||
_connected = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool DisConnect()
|
||||
{
|
||||
if (!_connected)
|
||||
throw new InvalidOperationException("Already DisConnected");
|
||||
_connected = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
#endregion
|
||||
}
|
||||
}
|
@ -1,31 +0,0 @@
|
||||
using System.ComponentModel;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public abstract class NotifyProperyChangedBase : INotifyPropertyChanged, ISupportsExternalInvokedInpc
|
||||
{
|
||||
public event PropertyChangedEventHandler PropertyChanged;
|
||||
|
||||
protected bool CheckPropertyChanged<T>(string propertyName, ref T oldValue, ref T newValue)
|
||||
{
|
||||
if (oldValue == null && newValue == null)
|
||||
return false;
|
||||
|
||||
if ((oldValue == null && newValue != null) || !oldValue.Equals((T)newValue))
|
||||
{
|
||||
oldValue = newValue;
|
||||
FirePropertyChanged(propertyName);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
public void FirePropertyChanged(string propertyName)
|
||||
{
|
||||
if (PropertyChanged != null)
|
||||
PropertyChanged(this, new PropertyChangedEventArgs(propertyName));
|
||||
}
|
||||
|
||||
}
|
||||
}
|
@ -1,34 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class AcroModeConfigVm : ConfigWithPidsBase
|
||||
{
|
||||
public AcroModeConfigVm()
|
||||
{
|
||||
updateString = "O";
|
||||
refreshString = "P";
|
||||
|
||||
PropsInUpdateOrder = new[]
|
||||
{
|
||||
"RollP",
|
||||
"RollI",
|
||||
"RollD",
|
||||
"PitchP",
|
||||
"PitchI",
|
||||
"PitchD",
|
||||
"YawP",
|
||||
"YawI",
|
||||
"YawD",
|
||||
"TransmitterFactor",
|
||||
};
|
||||
}
|
||||
|
||||
public float TransmitterFactor { get; set; }
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Acro Mode"; }
|
||||
}
|
||||
}
|
||||
}
|
@ -1,71 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
/// <summary>
|
||||
/// Vm for Altitude hold settings
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// Todo: this one is weird because the APM sends and receives the values
|
||||
/// in a different order
|
||||
/// There is a unit test to cover it but it will need fixing.
|
||||
/// TODO: test this
|
||||
/// </remarks>
|
||||
public class AltitudeHoldConfigVm : CrudVm
|
||||
{
|
||||
public AltitudeHoldConfigVm()
|
||||
{
|
||||
updateString = "E";
|
||||
refreshString = "F";
|
||||
PropsInUpdateOrder = new[] {"P", "I", "D",};
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
private float _p;
|
||||
public float P
|
||||
{
|
||||
get { return _p; }
|
||||
set
|
||||
{
|
||||
if (_p == value) return;
|
||||
_p = value;
|
||||
FirePropertyChanged("P");
|
||||
}
|
||||
}
|
||||
|
||||
private float _i;
|
||||
|
||||
public float I
|
||||
{
|
||||
get { return _i; }
|
||||
set
|
||||
{
|
||||
if (_i == value) return;
|
||||
_i = value;
|
||||
FirePropertyChanged("I");
|
||||
}
|
||||
}
|
||||
|
||||
private float _d;
|
||||
|
||||
public float D
|
||||
{
|
||||
get { return _d; }
|
||||
set
|
||||
{
|
||||
if (_d == value) return;
|
||||
_d = value;
|
||||
FirePropertyChanged("D");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Altitude Hold"; }
|
||||
}
|
||||
}
|
||||
}
|
@ -1,129 +0,0 @@
|
||||
using System.Collections.Generic;
|
||||
using System.Diagnostics;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public abstract class ConfigWithPidsBase : CrudVm
|
||||
{
|
||||
|
||||
private float _rollP;
|
||||
|
||||
public float RollP
|
||||
{
|
||||
get { return _rollP; }
|
||||
set
|
||||
{
|
||||
if (_rollP == value) return;
|
||||
_rollP = value;
|
||||
FirePropertyChanged("RollP");
|
||||
}
|
||||
}
|
||||
|
||||
private float _rolli;
|
||||
|
||||
public float RollI
|
||||
{
|
||||
get { return _rolli; }
|
||||
set
|
||||
{
|
||||
if (_rolli == value) return;
|
||||
_rolli = value;
|
||||
FirePropertyChanged("RollI");
|
||||
}
|
||||
}
|
||||
|
||||
private float _rollD;
|
||||
|
||||
public float RollD
|
||||
{
|
||||
get { return _rollD; }
|
||||
set
|
||||
{
|
||||
if (_rollD == value) return;
|
||||
_rollD = value;
|
||||
FirePropertyChanged("RollD");
|
||||
}
|
||||
}
|
||||
|
||||
private float _pitchP;
|
||||
|
||||
public float PitchP
|
||||
{
|
||||
get { return _pitchP; }
|
||||
set
|
||||
{
|
||||
if (_pitchP == value) return;
|
||||
_pitchP = value;
|
||||
FirePropertyChanged("PitchP");
|
||||
}
|
||||
}
|
||||
|
||||
private float _pitchI;
|
||||
|
||||
public float PitchI
|
||||
{
|
||||
get { return _pitchI; }
|
||||
set
|
||||
{
|
||||
if (_pitchI == value) return;
|
||||
_pitchI = value;
|
||||
FirePropertyChanged("PitchI");
|
||||
}
|
||||
}
|
||||
|
||||
private float _pitchD;
|
||||
|
||||
public float PitchD
|
||||
{
|
||||
get { return _pitchD; }
|
||||
set
|
||||
{
|
||||
if (_pitchD == value) return;
|
||||
_pitchD = value;
|
||||
FirePropertyChanged("PitchD");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private float _yawP;
|
||||
|
||||
public float YawP
|
||||
{
|
||||
get { return _yawP; }
|
||||
set
|
||||
{
|
||||
if (_yawP == value) return;
|
||||
_yawP = value;
|
||||
FirePropertyChanged("YawP");
|
||||
}
|
||||
}
|
||||
|
||||
private float _yawI;
|
||||
|
||||
public float YawI
|
||||
{
|
||||
get { return _yawI; }
|
||||
set
|
||||
{
|
||||
if (_yawI == value) return;
|
||||
_yawI = value;
|
||||
FirePropertyChanged("YawI");
|
||||
}
|
||||
}
|
||||
|
||||
private float _yawD;
|
||||
|
||||
public float YawD
|
||||
{
|
||||
get { return _yawD; }
|
||||
set
|
||||
{
|
||||
if (_yawD == value) return;
|
||||
_yawD = value;
|
||||
FirePropertyChanged("YawD");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,82 +0,0 @@
|
||||
using System;
|
||||
using System.ComponentModel;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
/// <summary>
|
||||
/// Common base for the simple VMs that deal with an update from APM and Get and Update them
|
||||
/// </summary>
|
||||
public abstract class CrudVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
protected string updateString;
|
||||
protected string refreshString;
|
||||
|
||||
// true when we are populating the properties from a serial command
|
||||
protected bool _apmUpdatingProperties;
|
||||
|
||||
protected CrudVm()
|
||||
{
|
||||
RefreshCommand = new DelegateCommand(_ => RefreshValues());
|
||||
UpdateCommand = new DelegateCommand(_ => UpdateValues());
|
||||
PropertyChanged += AltitudeHoldConfigVm_PropertyChanged;
|
||||
}
|
||||
|
||||
void AltitudeHoldConfigVm_PropertyChanged(object sender, PropertyChangedEventArgs e)
|
||||
{
|
||||
// When this happens, a property has been set either when the user has adjusted it,
|
||||
// or when the APM has sent us an update, probably due to an refresh command.
|
||||
if (!_apmUpdatingProperties)
|
||||
{
|
||||
// Since here we know it was the user updating. Send to the apm
|
||||
UpdateValues();
|
||||
}
|
||||
}
|
||||
|
||||
public string[] PropsInUpdateOrder { get; protected set; }
|
||||
|
||||
public ICommand RefreshCommand { get; private set; }
|
||||
|
||||
public ICommand UpdateCommand { get; private set; }
|
||||
|
||||
protected void RefreshValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(refreshString));
|
||||
}
|
||||
|
||||
protected void UpdateValues()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
{
|
||||
var apmString = PropertyHelper.ComposePropValuesWithCommand(this, PropsInUpdateOrder, updateString);
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(apmString));
|
||||
}
|
||||
}
|
||||
|
||||
public abstract string Name { get; }
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
RefreshValues();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
_apmUpdatingProperties = true;
|
||||
PropertyHelper.PopulatePropsFromUpdate(this,PropsInUpdateOrder, strRx,false);
|
||||
_apmUpdatingProperties = false;
|
||||
|
||||
if (updatedByApm != null)
|
||||
updatedByApm(this, EventArgs.Empty);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
}
|
||||
}
|
@ -1,87 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public abstract class DoubleVm<Tvm1,Tvm2> : NotifyProperyChangedBase, IPresentationModel
|
||||
where Tvm1 : IPresentationModel
|
||||
where Tvm2 : IPresentationModel
|
||||
{
|
||||
protected Tvm1 _vm1;
|
||||
protected Tvm2 _vm2;
|
||||
protected IPresentationModel _activeVm;
|
||||
|
||||
|
||||
protected DoubleVm(Tvm1 _vm1, Tvm2 _vm2)
|
||||
{
|
||||
this._vm1 = _vm1;
|
||||
this._vm2 = _vm2;
|
||||
|
||||
_vm1.sendTextToApm += proxyApmTx;
|
||||
_vm2.sendTextToApm += proxyApmTx;
|
||||
}
|
||||
|
||||
private void proxyApmTx(object sender, sendTextToApmEventArgs e)
|
||||
{
|
||||
_activeVm = sender as IPresentationModel;
|
||||
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, e);
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
_activeVm.handleLineOfText(strRx);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
|
||||
public abstract string Name { get; }
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
_vm1.updatedByApm += _vm1_updatedByApm;
|
||||
_vm1.Activate();
|
||||
}
|
||||
|
||||
void _vm1_updatedByApm(object sender, EventArgs e)
|
||||
{
|
||||
// This is a response to the refresh event being completed on the first
|
||||
// vm, so refresh the second. Unsubscribe so that the vms respond
|
||||
// individually to refresh commands henceforth
|
||||
_vm1.updatedByApm -= _vm1_updatedByApm;
|
||||
_vm2.Activate();
|
||||
}
|
||||
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
_vm1.DeActivate();
|
||||
_vm2.DeActivate();
|
||||
}
|
||||
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public Tvm1 Vm1
|
||||
{
|
||||
get { return _vm1; }
|
||||
set
|
||||
{
|
||||
_vm1 = value;
|
||||
FirePropertyChanged("Vm1");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public Tvm2 Vm2
|
||||
{
|
||||
get { return _vm2; }
|
||||
set
|
||||
{
|
||||
_vm2 = value;
|
||||
FirePropertyChanged("Vm2");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -1,19 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class FlightControlPidsVm : DoubleVm<AcroModeConfigVm, StableModeConfigVm>
|
||||
{
|
||||
public FlightControlPidsVm() : base(new AcroModeConfigVm(), new StableModeConfigVm())
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Flight Control"; }
|
||||
}
|
||||
}
|
||||
}
|
@ -1,218 +0,0 @@
|
||||
using System;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Globalization;
|
||||
using System.IO;
|
||||
using System.Net;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class GpsStatusVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
private const string SEND_GPS_DATA = "4";
|
||||
private const string STOP_UPDATES = "X";
|
||||
|
||||
public ICommand GetMapCommand { get; private set; }
|
||||
|
||||
private BackgroundWorker bg;
|
||||
|
||||
public GpsStatusVm()
|
||||
{
|
||||
bg = new BackgroundWorker();
|
||||
bg.DoWork += DownloadGoogleMap;
|
||||
bg.RunWorkerCompleted += DownloadGoogleMapComplete;
|
||||
|
||||
GetMapCommand = new DelegateCommand(_ => GetMap(), _=> HasFix && !bg.IsBusy);
|
||||
}
|
||||
|
||||
private void GetMap()
|
||||
{
|
||||
var urlTemplate =
|
||||
"http://maps.google.com/maps/api/staticmap?&markers=color:blue|label:A|{0:0.00000},{1:0.00000}&zoom=13&size=250x200&maptype=roadmap&sensor=false";
|
||||
|
||||
var url = string.Format(CultureInfo.InvariantCulture, urlTemplate, GpsLatitude, GpsLongitude);
|
||||
|
||||
bg.RunWorkerAsync(url);
|
||||
}
|
||||
|
||||
private void DownloadGoogleMapComplete(object sender, RunWorkerCompletedEventArgs e)
|
||||
{
|
||||
MapImage = e.Result as Image;
|
||||
}
|
||||
|
||||
private void DownloadGoogleMap(object sender, DoWorkEventArgs e)
|
||||
{
|
||||
var url = e.Argument as string;
|
||||
var Client = new WebClient();
|
||||
using (var strm = Client.OpenRead(url))
|
||||
{
|
||||
var png = Image.FromStream(strm);
|
||||
e.Result = png;
|
||||
}
|
||||
}
|
||||
|
||||
private void sendString(string str)
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(str));
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
sendString(SEND_GPS_DATA);
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
sendString(STOP_UPDATES);
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
|
||||
public string Name
|
||||
{
|
||||
get { return "GPS Status"; }
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
// We don't bother with the automatic property population, as the received string is
|
||||
// tab delimeted and the values have crazy scale factors anyway.
|
||||
|
||||
// hack for testing with no GPS
|
||||
// strRx = "73410000\t407021470\t-740157940\t9242\t0\t19831\t1";
|
||||
|
||||
var parts = strRx.Split('\t');
|
||||
try
|
||||
{
|
||||
GpsTime = int.Parse(parts[0].Trim(), CultureInfo.InvariantCulture);
|
||||
GpsLatitude = (float)(int.Parse(parts[1].Trim(), CultureInfo.InvariantCulture)) / 10000000;
|
||||
GpsLongitude = (float)(int.Parse(parts[2].Trim(), CultureInfo.InvariantCulture)) / 10000000;
|
||||
GpsAltitude = int.Parse(parts[3].Trim(), CultureInfo.InvariantCulture) / 100;
|
||||
GpsGroundSpeed = (float)(int.Parse(parts[4].Trim(), CultureInfo.InvariantCulture)) / 100;
|
||||
GpsGroundCourse = int.Parse(parts[5].Trim(), CultureInfo.InvariantCulture) / 100;
|
||||
HasFix = parts[6].Trim() == "1";
|
||||
|
||||
// Todo: the number of sats is actually a raw char, not an ascii char like '3'
|
||||
}
|
||||
catch (FormatException)
|
||||
{
|
||||
Console.WriteLine("Format Exception in GPS VM, string: " + strRx);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
#region bindables
|
||||
|
||||
private Image _mapImage;
|
||||
|
||||
public Image MapImage
|
||||
{
|
||||
get { return _mapImage; }
|
||||
set
|
||||
{
|
||||
if (_mapImage == value) return;
|
||||
_mapImage = value;
|
||||
FirePropertyChanged("MapImage");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private int _gpsTime;
|
||||
|
||||
public int GpsTime
|
||||
{
|
||||
get { return _gpsTime; }
|
||||
set
|
||||
{
|
||||
if (_gpsTime == value) return;
|
||||
_gpsTime = value;
|
||||
FirePropertyChanged("GpsTime");
|
||||
}
|
||||
}
|
||||
|
||||
private float _gpsLatitude;
|
||||
|
||||
public float GpsLatitude
|
||||
{
|
||||
get { return _gpsLatitude; }
|
||||
set
|
||||
{
|
||||
if (_gpsLatitude == value) return;
|
||||
_gpsLatitude = value;
|
||||
FirePropertyChanged("GpsLatitude");
|
||||
}
|
||||
}
|
||||
|
||||
private float _gpsLongitude;
|
||||
|
||||
public float GpsLongitude
|
||||
{
|
||||
get { return _gpsLongitude; }
|
||||
set
|
||||
{
|
||||
if (_gpsLongitude == value) return;
|
||||
_gpsLongitude = value;
|
||||
FirePropertyChanged("GpsLongitude");
|
||||
}
|
||||
}
|
||||
|
||||
private float _gpsGroundSpeed;
|
||||
|
||||
public float GpsGroundSpeed
|
||||
{
|
||||
get { return _gpsGroundSpeed; }
|
||||
set
|
||||
{
|
||||
if (_gpsGroundSpeed == value) return;
|
||||
_gpsGroundSpeed = value;
|
||||
FirePropertyChanged("GpsGroundSpeed");
|
||||
}
|
||||
}
|
||||
|
||||
private int _gpsGroundCourse;
|
||||
|
||||
public int GpsGroundCourse
|
||||
{
|
||||
get { return _gpsGroundCourse; }
|
||||
set
|
||||
{
|
||||
if (_gpsGroundCourse == value) return;
|
||||
_gpsGroundCourse = value;
|
||||
FirePropertyChanged("GpsGroundCourse");
|
||||
}
|
||||
}
|
||||
|
||||
private int _gpsAltitude;
|
||||
|
||||
public int GpsAltitude
|
||||
{
|
||||
get { return _gpsAltitude; }
|
||||
set
|
||||
{
|
||||
if (_gpsAltitude == value) return;
|
||||
_gpsAltitude = value;
|
||||
FirePropertyChanged("GpsAltitude");
|
||||
}
|
||||
}
|
||||
|
||||
private bool _hasFix;
|
||||
|
||||
public bool HasFix
|
||||
{
|
||||
get { return _hasFix; }
|
||||
set
|
||||
{
|
||||
if (_hasFix == value) return;
|
||||
_hasFix = value;
|
||||
FirePropertyChanged("HasFix");
|
||||
}
|
||||
}
|
||||
|
||||
#endregion
|
||||
}
|
||||
}
|
@ -1,21 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public interface ItalksToApm
|
||||
{
|
||||
void handleLineOfText(string strRx);
|
||||
event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
}
|
||||
|
||||
public class sendTextToApmEventArgs : EventArgs
|
||||
{
|
||||
public string textToSend;
|
||||
|
||||
public sendTextToApmEventArgs(string textToSend)
|
||||
{
|
||||
this.textToSend = textToSend;
|
||||
}
|
||||
}
|
||||
}
|
@ -1,298 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using Timer=System.Windows.Forms.Timer;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class MainVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
private readonly IComms _comms;
|
||||
private bool _isConnected;
|
||||
private IPresentationModel _selectedVm;
|
||||
private string _selectedPort;
|
||||
private int _selectedBaudRate;
|
||||
private string _apmVersion;
|
||||
private Timer _connectionAttemptsTimer;
|
||||
|
||||
private SessionStates _connectionState;
|
||||
|
||||
|
||||
public MainVm(IComms session)
|
||||
{
|
||||
_comms = session;
|
||||
_comms.LineOfDataReceived += _session_LineOfDataReceived;
|
||||
|
||||
MonitorVms = new BindingList<IPresentationModel>
|
||||
{
|
||||
new SensorsVm(),
|
||||
new TransmitterChannelsVm(),
|
||||
new FlightControlPidsVm(),
|
||||
new PositionAltitudePidsVm(),
|
||||
new GpsStatusVm(),
|
||||
|
||||
//new MotorCommandsVm(session),
|
||||
new SerialMonitorVm(),
|
||||
};
|
||||
|
||||
foreach (var vm in MonitorVms)
|
||||
{
|
||||
if (vm is ItalksToApm)
|
||||
vm.sendTextToApm += MainVm_sendTextToApm;
|
||||
}
|
||||
|
||||
ConnectCommand = new DelegateCommand(
|
||||
_ => Connect(),
|
||||
_ => _connectionState==SessionStates.Disconnected && AvailablePorts.Contains(SelectedPort));
|
||||
|
||||
DisconnectCommand = new DelegateCommand(_ => Disconnect(), _ => IsConnected);
|
||||
|
||||
RefreshPortListCommand = new DelegateCommand(_ => RefreshPorts());
|
||||
|
||||
RestoreDefaultsCommand = new DelegateCommand(_ => RestoreDefaults(), _ => IsConnected);
|
||||
|
||||
WriteToEepromCommand = new DelegateCommand(_ => WriteToEeprom(), _ => IsConnected);
|
||||
|
||||
ConnectionState = SessionStates.Disconnected;
|
||||
|
||||
AvailablePorts = new BindingList<string>();
|
||||
|
||||
AvailableBaudRates = new BindingList<int>() {115200, 57600, 38400, 9600};
|
||||
SelectedBaudRate = 115200;
|
||||
|
||||
RefreshPorts();
|
||||
|
||||
// Initially have selected the last discovered com port.
|
||||
// I think this is more likely to be the correct one, as
|
||||
// the built in comports come first, then the usb/serial
|
||||
// converter ports
|
||||
if (AvailablePorts.Count > 0)
|
||||
SelectedPort = AvailablePorts[AvailablePorts.Count-1];
|
||||
}
|
||||
|
||||
|
||||
|
||||
void MainVm_sendTextToApm(object sender, sendTextToApmEventArgs e)
|
||||
{
|
||||
if (sender.Equals(_selectedVm)==false)
|
||||
{
|
||||
Console.WriteLine("Non selected vm wants to send something to the APM");
|
||||
return;
|
||||
}
|
||||
|
||||
if (_comms.IsConnected)
|
||||
_comms.Send(e.textToSend);
|
||||
|
||||
}
|
||||
|
||||
private void RefreshPorts()
|
||||
{
|
||||
AvailablePorts.Clear();
|
||||
foreach (var c in _comms.ListCommPorts())
|
||||
AvailablePorts.Add(c);
|
||||
}
|
||||
|
||||
private void RestoreDefaults()
|
||||
{
|
||||
if (_comms.IsConnected)
|
||||
_comms.Send("Y");
|
||||
}
|
||||
|
||||
private void WriteToEeprom()
|
||||
{
|
||||
if (_comms.IsConnected)
|
||||
_comms.Send("W");
|
||||
}
|
||||
|
||||
void _session_LineOfDataReceived(string strRx)
|
||||
{
|
||||
// If we are waiting for the version string
|
||||
if (ConnectionState==SessionStates.Connecting)
|
||||
{
|
||||
if (strRx.Length > 6)
|
||||
return; // too long for a version string - reject
|
||||
|
||||
// then assume that this is the version string received
|
||||
ApmVersion = strRx;
|
||||
ConnectionState = SessionStates.Connected;
|
||||
_selectedVm.Activate();
|
||||
}
|
||||
else if (ConnectionState == SessionStates.Connected)
|
||||
{
|
||||
if (_selectedVm is ItalksToApm)
|
||||
(_selectedVm as ItalksToApm).handleLineOfText(strRx);
|
||||
}
|
||||
}
|
||||
|
||||
public ICommand ConnectCommand { get; private set; }
|
||||
|
||||
public ICommand DisconnectCommand { get; private set; }
|
||||
|
||||
public ICommand RefreshPortListCommand { get; private set; }
|
||||
|
||||
public ICommand RestoreDefaultsCommand { get; private set; }
|
||||
|
||||
public ICommand WriteToEepromCommand { get; private set; }
|
||||
|
||||
public BindingList<string> AvailablePorts { get; private set; }
|
||||
|
||||
public BindingList<int> AvailableBaudRates { get; private set; }
|
||||
|
||||
public enum SessionStates
|
||||
{
|
||||
Disconnected,
|
||||
Connecting,
|
||||
Connected,
|
||||
}
|
||||
|
||||
public SessionStates ConnectionState
|
||||
{
|
||||
get { return _connectionState; }
|
||||
set
|
||||
{
|
||||
if (_connectionState != value)
|
||||
{
|
||||
_connectionState = value;
|
||||
IsConnected = _connectionState == SessionStates.Connected;
|
||||
FirePropertyChanged("ConnectionState");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// provided for convenience for binding set from the session state prop
|
||||
public bool IsConnected
|
||||
{
|
||||
get { return _isConnected; }
|
||||
private set
|
||||
{
|
||||
if (_isConnected != value)
|
||||
{
|
||||
_isConnected = value;
|
||||
FirePropertyChanged("IsConnected");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public string SelectedPort
|
||||
{
|
||||
get { return _selectedPort; }
|
||||
set
|
||||
{
|
||||
if (_selectedPort != value)
|
||||
{
|
||||
_selectedPort = value;
|
||||
FirePropertyChanged("SelectedPort");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public int SelectedBaudRate
|
||||
{
|
||||
get { return _selectedBaudRate; }
|
||||
set
|
||||
{
|
||||
if (_selectedBaudRate != value)
|
||||
{
|
||||
_selectedBaudRate = value;
|
||||
FirePropertyChanged("SelectedBaudRate");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public void Connect()
|
||||
{
|
||||
_comms.CommPort = SelectedPort;
|
||||
_comms.BaudRate = SelectedBaudRate;
|
||||
|
||||
// Todo: check the status of this call success/failure
|
||||
if (!_comms.Connect())
|
||||
{
|
||||
ConnectionState = SessionStates.Disconnected;
|
||||
ApmVersion = "Error";
|
||||
return;
|
||||
}
|
||||
|
||||
ConnectionState = SessionStates.Connecting;
|
||||
|
||||
_connectionAttemptsTimer = new Timer();
|
||||
_connectionAttemptsTimer.Tick += _connectionAttemptsTimer_Tick;
|
||||
_connectionAttemptsTimer.Interval = 1000; //milliseconds
|
||||
_connectionAttemptsTimer.Start();
|
||||
}
|
||||
|
||||
void _connectionAttemptsTimer_Tick(object sender, EventArgs e)
|
||||
{
|
||||
if (_connectionState != SessionStates.Connecting)
|
||||
{
|
||||
_connectionAttemptsTimer.Stop();
|
||||
return;
|
||||
}
|
||||
_comms.Send("X");
|
||||
|
||||
// once we connected, then get the version string
|
||||
_comms.Send("!");
|
||||
}
|
||||
|
||||
public void Disconnect()
|
||||
{
|
||||
_comms.Send("X");
|
||||
_comms.DisConnect();
|
||||
ConnectionState = SessionStates.Disconnected;
|
||||
}
|
||||
|
||||
public string ApmVersion
|
||||
{
|
||||
get { return _apmVersion; }
|
||||
private set
|
||||
{
|
||||
if (_apmVersion != value)
|
||||
{
|
||||
_apmVersion = value;
|
||||
FirePropertyChanged("ApmVersion");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public BindingList<IPresentationModel> MonitorVms { get; private set; }
|
||||
|
||||
public string Name
|
||||
{
|
||||
get { return "Arducopter Config"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
throw new System.NotImplementedException();
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
throw new System.NotImplementedException();
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public void Select(IPresentationModel vm)
|
||||
{
|
||||
if (_selectedVm==vm)
|
||||
return;
|
||||
|
||||
if (vm == null)
|
||||
throw new ArgumentNullException("vm");
|
||||
|
||||
if (_selectedVm!=null)
|
||||
_selectedVm.DeActivate();
|
||||
|
||||
_selectedVm = vm;
|
||||
_selectedVm.Activate();
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
throw new System.NotImplementedException();
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
}
|
||||
}
|
@ -1,42 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class MotorCommandsVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
public string Name
|
||||
{
|
||||
get { return "Motor Commands"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
// todo stop
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public int MotorFront { get; set; }
|
||||
public int MotorRear { get; set; }
|
||||
public int MotorLeft { get; set; }
|
||||
public int MotorRight { get; set; }
|
||||
|
||||
public void SendCommand()
|
||||
{
|
||||
}
|
||||
|
||||
public void StopCommand()
|
||||
{
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
}
|
||||
}
|
@ -1,18 +0,0 @@
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class PositionAltitudePidsVm : DoubleVm<PositionHoldConfigVm,AltitudeHoldConfigVm>
|
||||
{
|
||||
public PositionAltitudePidsVm() : base(new PositionHoldConfigVm(), new AltitudeHoldConfigVm())
|
||||
{
|
||||
}
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Position & Altitude"; }
|
||||
}
|
||||
|
||||
}
|
||||
}
|
@ -1,34 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class PositionHoldConfigVm : ConfigWithPidsBase
|
||||
{
|
||||
public PositionHoldConfigVm()
|
||||
{
|
||||
updateString = "C";
|
||||
refreshString = "D";
|
||||
|
||||
PropsInUpdateOrder = new[]
|
||||
{
|
||||
"RollP",
|
||||
"RollI",
|
||||
"RollD",
|
||||
"PitchP",
|
||||
"PitchI",
|
||||
"PitchD",
|
||||
"MaximumAngle",
|
||||
"GeoCorrectionFactor",
|
||||
};
|
||||
}
|
||||
|
||||
public float MaximumAngle { get; set; }
|
||||
|
||||
public float GeoCorrectionFactor { get; set; }
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Position Hold"; }
|
||||
}
|
||||
}
|
||||
}
|
@ -1,406 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Diagnostics;
|
||||
using System.IO.Ports;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
/// <summary>
|
||||
/// View Model for the sensors monitor and calibration
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// This tab is for the monitoring and calibration of the Gyro/Accel sensors
|
||||
///
|
||||
/// When it is activated, it retrieves the current sensor calibration values
|
||||
/// Then, it requests the constant stream of sensor readings in order to provide
|
||||
/// a live view.
|
||||
///
|
||||
/// The user can change the calibration offsets, and upload the new values.
|
||||
/// When this happens, the model tells the APM to cease sending the realtime updates,
|
||||
/// then sends the new offset values, then resumes the updates
|
||||
///
|
||||
/// There is a command to automatically fill the sensor offset values, from the
|
||||
/// current values of the sensors. The user would do this when the copter is
|
||||
/// sitting still and level
|
||||
///
|
||||
/// When the VM is deactivated, the model tells the APM to cease sending the realtime updates
|
||||
/// </remarks>
|
||||
public class SensorsVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
|
||||
private const string CALIB_REFRESH = "J";
|
||||
private const string CALIB_UPDATE = "I";
|
||||
private const string SEND_SENSOR_DATA = "S";
|
||||
private const string STOP_UPDATES = "X";
|
||||
|
||||
private bool waitingForCalibData;
|
||||
|
||||
public SensorsVm()
|
||||
{
|
||||
RefreshCalibrationOffsetsCommand = new DelegateCommand(_ => RefreshCalibValues());
|
||||
UpdateCalibrationOffsetsCommand = new DelegateCommand(_ => UpdateCalibValues());
|
||||
CalculateCalibrationOffsetsCommand = new DelegateCommand(_ => CalcCalibValues());
|
||||
|
||||
PropertyChanged += ((sender, e) =>
|
||||
{
|
||||
IsArmed = !(MotorFront == 1040 && MotorRear == 1040 && MotorLeft == 1040 && MotorRight == 1040);
|
||||
});
|
||||
}
|
||||
|
||||
public void RefreshCalibValues()
|
||||
{
|
||||
sendString(STOP_UPDATES);
|
||||
waitingForCalibData = true;
|
||||
sendString(CALIB_REFRESH);
|
||||
}
|
||||
|
||||
public void UpdateCalibValues()
|
||||
{
|
||||
sendString(PropertyHelper.ComposePropValuesWithCommand(this, _calibrationPropsInUpdateOrder, CALIB_UPDATE));
|
||||
sendString(SEND_SENSOR_DATA);
|
||||
}
|
||||
|
||||
public void CalcCalibValues()
|
||||
{
|
||||
AccelRollOffset = AccelRollOffset - AccelRoll;
|
||||
AccelPitchOffset = AccelPitchOffset - AccelPitch;
|
||||
//AccelZOffset = AccelZOffset - AccelZ;
|
||||
FirePropertyChanged("AccelRollOffset");
|
||||
FirePropertyChanged("AccelPitchOffset");
|
||||
//FirePropertyChanged("AccelZOffset");
|
||||
}
|
||||
|
||||
public string Name
|
||||
{
|
||||
get { return "Sensor Data"; }
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
private readonly string[] _sensorPropsInUpdateOrder = new[]
|
||||
{
|
||||
"LoopTime",
|
||||
"GyroRoll",
|
||||
"GyroPitch",
|
||||
"GyroYaw",
|
||||
"Unused", // Throttle
|
||||
"ControlRoll", // control roll
|
||||
"ControlPitch", // control pitch
|
||||
"ControlYaw", // control yaw
|
||||
"MotorFront",
|
||||
"MotorRear",
|
||||
"MotorRight",
|
||||
"MotorLeft",
|
||||
"AccelRoll",
|
||||
"AccelPitch",
|
||||
"AccelZ",
|
||||
"CompassHeading", // AP_Compass.heading
|
||||
"UnusedFloat", // AP_Compass.heading_x
|
||||
"UnusedFloat", // AP_Compass.heading_y
|
||||
"Unused", // AP_Compass.mag_x
|
||||
"Unused", // AP_Compass.mag_y
|
||||
"Unused", // AP_Compass.mag_z
|
||||
|
||||
};
|
||||
|
||||
private readonly string[] _calibrationPropsInUpdateOrder = new[]
|
||||
{
|
||||
"GyroRollOffset",
|
||||
"GyroPitchOffset",
|
||||
"GyroYawOffset",
|
||||
"AccelRollOffset",
|
||||
"AccelPitchOffset",
|
||||
"AccelZOffset"
|
||||
};
|
||||
|
||||
|
||||
private void sendString(string str)
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(str));
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
// Get the calib. data first
|
||||
waitingForCalibData = true;
|
||||
sendString(CALIB_REFRESH);
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
sendString(STOP_UPDATES);
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
if ( waitingForCalibData)
|
||||
{
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, _calibrationPropsInUpdateOrder, strRx, true);
|
||||
waitingForCalibData = false;
|
||||
sendString(SEND_SENSOR_DATA);
|
||||
}
|
||||
else
|
||||
{
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, _sensorPropsInUpdateOrder, strRx, false);
|
||||
}
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
public ICommand RefreshCalibrationOffsetsCommand { get; private set; }
|
||||
|
||||
public ICommand UpdateCalibrationOffsetsCommand { get; private set; }
|
||||
|
||||
public ICommand CalculateCalibrationOffsetsCommand { get; private set; }
|
||||
|
||||
|
||||
#region Calibration Properties
|
||||
|
||||
public float GyroRollOffset { get; set; }
|
||||
public float GyroPitchOffset { get; set; }
|
||||
public float GyroYawOffset { get; set; }
|
||||
|
||||
public float AccelRollOffset { get; set; }
|
||||
public float AccelPitchOffset { get; set; }
|
||||
public float AccelZOffset { get; set; }
|
||||
|
||||
|
||||
#endregion
|
||||
|
||||
|
||||
private bool _isArmed;
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Whether the Arducopter is Armed or not
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// We don't get this information directly, but we can infer it if all motors are
|
||||
/// at 1040 then the thing is NOT armed.
|
||||
/// </remarks>
|
||||
public bool IsArmed
|
||||
{
|
||||
get { return _isArmed; }
|
||||
set
|
||||
{
|
||||
if (_isArmed == value) return;
|
||||
_isArmed = value;
|
||||
FirePropertyChanged("IsArmed");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#region Sensor Properties
|
||||
|
||||
private int _loopTime;
|
||||
public int LoopTime
|
||||
{
|
||||
get { return _loopTime; }
|
||||
set
|
||||
{
|
||||
if (_loopTime == value) return;
|
||||
_loopTime = value;
|
||||
FirePropertyChanged("LoopTime");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private int motorFront;
|
||||
public int MotorFront
|
||||
{
|
||||
get { return motorFront; }
|
||||
set {
|
||||
if (motorFront == value) return;
|
||||
motorFront = value;
|
||||
FirePropertyChanged("MotorFront");
|
||||
}
|
||||
}
|
||||
|
||||
private int motorRear;
|
||||
public int MotorRear
|
||||
{
|
||||
get { return motorRear; }
|
||||
set
|
||||
{
|
||||
if (motorRear == value) return;
|
||||
motorRear = value;
|
||||
FirePropertyChanged("MotorRear");
|
||||
}
|
||||
}
|
||||
|
||||
private int motorLeft;
|
||||
public int MotorLeft
|
||||
{
|
||||
get { return motorLeft; }
|
||||
set
|
||||
{
|
||||
if (motorLeft == value) return;
|
||||
motorLeft = value;
|
||||
FirePropertyChanged("MotorLeft");
|
||||
}
|
||||
}
|
||||
|
||||
private int motorRight;
|
||||
public int MotorRight
|
||||
{
|
||||
get { return motorRight; }
|
||||
set
|
||||
{
|
||||
if (motorRight == value) return;
|
||||
motorRight = value;
|
||||
FirePropertyChanged("MotorRight");
|
||||
}
|
||||
}
|
||||
|
||||
private int gyroPitch;
|
||||
public int GyroPitch
|
||||
{
|
||||
get { return gyroPitch; }
|
||||
set
|
||||
{
|
||||
if (gyroPitch == value) return;
|
||||
gyroPitch = value;
|
||||
FirePropertyChanged("GyroPitch");
|
||||
}
|
||||
}
|
||||
|
||||
private int gyroRoll;
|
||||
public int GyroRoll
|
||||
{
|
||||
get { return gyroRoll; }
|
||||
set
|
||||
{
|
||||
if (gyroRoll == value) return;
|
||||
gyroRoll = value;
|
||||
FirePropertyChanged("GyroRoll");
|
||||
}
|
||||
}
|
||||
|
||||
private int gyroYaw;
|
||||
public int GyroYaw
|
||||
{
|
||||
get { return gyroYaw; }
|
||||
set
|
||||
{
|
||||
if (gyroYaw == value) return;
|
||||
gyroYaw = value;
|
||||
FirePropertyChanged("GyroYaw");
|
||||
}
|
||||
}
|
||||
|
||||
private int accelPitch;
|
||||
public int AccelPitch
|
||||
{
|
||||
get { return accelPitch; }
|
||||
set
|
||||
{
|
||||
if (accelPitch == value) return;
|
||||
accelPitch = value;
|
||||
FirePropertyChanged("AccelPitch");
|
||||
}
|
||||
}
|
||||
|
||||
private int accelRoll;
|
||||
public int AccelRoll
|
||||
{
|
||||
get { return accelRoll; }
|
||||
set
|
||||
{
|
||||
if (accelRoll == value) return;
|
||||
accelRoll = value;
|
||||
FirePropertyChanged("AccelRoll");
|
||||
}
|
||||
}
|
||||
|
||||
private int accelZ;
|
||||
|
||||
public int AccelZ
|
||||
{
|
||||
get { return accelZ; }
|
||||
set
|
||||
{
|
||||
if (accelZ == value) return;
|
||||
accelZ = value;
|
||||
FirePropertyChanged("AccelZ");
|
||||
}
|
||||
}
|
||||
|
||||
private int _controlRoll;
|
||||
|
||||
public int ControlRoll
|
||||
{
|
||||
get { return _controlRoll; }
|
||||
set
|
||||
{
|
||||
if (_controlRoll == value) return;
|
||||
_controlRoll = value;
|
||||
FirePropertyChanged("ControlRoll");
|
||||
}
|
||||
}
|
||||
|
||||
private int _controlPitch;
|
||||
|
||||
public int ControlPitch
|
||||
{
|
||||
get { return _controlPitch; }
|
||||
set
|
||||
{
|
||||
if (_controlPitch == value) return;
|
||||
_controlPitch = value;
|
||||
FirePropertyChanged("ControlPitch");
|
||||
}
|
||||
}
|
||||
|
||||
private int _controlYaw;
|
||||
|
||||
public int ControlYaw
|
||||
{
|
||||
get { return _controlYaw; }
|
||||
set
|
||||
{
|
||||
if (_controlYaw == value) return;
|
||||
_controlYaw = value;
|
||||
FirePropertyChanged("ControlYaw");
|
||||
}
|
||||
}
|
||||
|
||||
private float _compassHeading;
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// The current compass Heading as read from the magnetometer in radians?
|
||||
/// </summary>
|
||||
public float CompassHeading
|
||||
{
|
||||
get { return _compassHeading; }
|
||||
set
|
||||
{
|
||||
if (_compassHeading == value) return;
|
||||
_compassHeading = value;
|
||||
FirePropertyChanged("CompassHeading");
|
||||
FirePropertyChanged("CompassHeadingDegrees");
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// The current compass Heading as read from the magnetometer in degrees
|
||||
/// </summary>
|
||||
public float CompassHeadingDegrees
|
||||
{
|
||||
get
|
||||
{
|
||||
var degrees = (float) ((CompassHeading) * (180 / Math.PI));
|
||||
return (360 + degrees) % 360;
|
||||
}
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
public int Unused { get; set; }
|
||||
public float UnusedFloat { get; set; }
|
||||
}
|
||||
}
|
@ -1,49 +0,0 @@
|
||||
using System;
|
||||
using System.IO.Ports;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class SerialMonitorVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
private string _text;
|
||||
|
||||
public string ReceviedText { get { return _text; } }
|
||||
|
||||
public string SendText { get; set; }
|
||||
|
||||
public string Name
|
||||
{
|
||||
get { return "Serial Monitor"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
_text = string.Empty;
|
||||
FirePropertyChanged("ReceviedText");
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
if (sendTextToApm!=null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs("X"));
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public void SendTextCommand()
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(SendText));
|
||||
SendText = "";
|
||||
FirePropertyChanged("SendText");
|
||||
}
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
_text += strRx + Environment.NewLine;
|
||||
FirePropertyChanged("ReceviedText");
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
}
|
||||
}
|
@ -1,61 +0,0 @@
|
||||
using System;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class StableModeConfigVm : ConfigWithPidsBase
|
||||
{
|
||||
public StableModeConfigVm()
|
||||
{
|
||||
updateString = "A";
|
||||
refreshString = "B";
|
||||
|
||||
PropsInUpdateOrder = new[]
|
||||
{
|
||||
"RollP",
|
||||
"RollI",
|
||||
"RollD",
|
||||
"PitchP",
|
||||
"PitchI",
|
||||
"PitchD",
|
||||
"YawP",
|
||||
"YawI",
|
||||
"YawD",
|
||||
"KPrate",
|
||||
"MagnetometerEnable",
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
private float _kprate;
|
||||
|
||||
public float KPrate
|
||||
{
|
||||
get { return _kprate; }
|
||||
set
|
||||
{
|
||||
if (_kprate == value) return;
|
||||
_kprate = value;
|
||||
FirePropertyChanged("KPrate");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private bool _magEnable;
|
||||
|
||||
public bool MagnetometerEnable
|
||||
{
|
||||
get { return _magEnable; }
|
||||
set
|
||||
{
|
||||
if (_magEnable == value) return;
|
||||
_magEnable = value;
|
||||
FirePropertyChanged("MagnetometerEnable");
|
||||
}
|
||||
}
|
||||
|
||||
public override string Name
|
||||
{
|
||||
get { return "Stable Mode"; }
|
||||
}
|
||||
}
|
||||
}
|
@ -1,454 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Diagnostics;
|
||||
|
||||
namespace ArducopterConfigurator.PresentationModels
|
||||
{
|
||||
public class TransmitterChannelsVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
private const string CALIB_REFRESH = "J";
|
||||
private const string CALIB_UPDATE = "I";
|
||||
private const string STOP_UPDATES = "X";
|
||||
private const string START_UPDATES = "U";
|
||||
private const string WRITE_TO_EEPROM = "W";
|
||||
|
||||
private bool _isCalibrating;
|
||||
|
||||
public bool IsCalibrating
|
||||
{
|
||||
get { return _isCalibrating; }
|
||||
set
|
||||
{
|
||||
_isCalibrating = value;
|
||||
FirePropertyChanged("IsCalibrating");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private readonly string[] _propsInUpdateOrder = new[]
|
||||
{
|
||||
"Roll", // Aileron
|
||||
"Pitch", // Elevator
|
||||
"Yaw",
|
||||
"Throttle",
|
||||
"Mode", // AUX1 (Mode)
|
||||
"Aux", // AUX2
|
||||
"RollMidValue",
|
||||
"PitchMidValue",
|
||||
"YawMidValue",
|
||||
};
|
||||
|
||||
|
||||
public TransmitterChannelsVm()
|
||||
{
|
||||
StartCalibrationCommand = new DelegateCommand(_ => BeginCalibration(),_=>!IsCalibrating);
|
||||
SaveCalibrationCommand = new DelegateCommand(_ => SaveCalibration(),_=> IsCalibrating);
|
||||
CancelCalibrationCommand = new DelegateCommand(_ => CancelCalibration(), _ => IsCalibrating);
|
||||
}
|
||||
|
||||
|
||||
private void sendString(string str)
|
||||
{
|
||||
if (sendTextToApm != null)
|
||||
sendTextToApm(this, new sendTextToApmEventArgs(str));
|
||||
}
|
||||
|
||||
private void BeginCalibration()
|
||||
{
|
||||
// send x command to stop jabber
|
||||
sendString(STOP_UPDATES);
|
||||
|
||||
ResetWatermarks();
|
||||
|
||||
IsCalibrating = true;
|
||||
|
||||
// send command to clear the slope and offsets
|
||||
// 11;0;1;0;1;0;1;0;1;0;1;0;
|
||||
sendString("11;0;1;0;1;0;1;0;1;0;1;0;");
|
||||
|
||||
// continue the sensor
|
||||
sendString(START_UPDATES);
|
||||
|
||||
}
|
||||
|
||||
|
||||
private void CancelCalibration()
|
||||
{
|
||||
IsCalibrating = false;
|
||||
HideWatermarks();
|
||||
}
|
||||
|
||||
private float GetScale(int min, int max)
|
||||
{
|
||||
var span = max - min;
|
||||
return 1000F / span;
|
||||
}
|
||||
|
||||
private int GetOffset(int min, int max)
|
||||
{
|
||||
return 0 - (int) ((min * GetScale(min,max)-1000));
|
||||
}
|
||||
|
||||
private void SaveCalibration()
|
||||
{
|
||||
// send values
|
||||
// eg 1.17,-291.91,1.18,-271.76,1.19,-313.91,1.18,-293.63,1.66,-1009.9
|
||||
|
||||
// ch_roll_slope = readFloatSerial();
|
||||
// ch_roll_offset = readFloatSerial();
|
||||
// ch_pitch_slope = readFloatSerial();
|
||||
// ch_pitch_offset = readFloatSerial();
|
||||
// ch_yaw_slope = readFloatSerial();
|
||||
// ch_yaw_offset = readFloatSerial();
|
||||
// ch_throttle_slope = readFloatSerial();
|
||||
// ch_throttle_offset = readFloatSerial();
|
||||
// ch_aux_slope = readFloatSerial();
|
||||
// ch_aux_offset = readFloatSerial();
|
||||
// ch_aux2_slope = readFloatSerial();
|
||||
// ch_aux2_offset = readFloatSerial();
|
||||
|
||||
// From Configurator:
|
||||
// 1.20,-331.74,1.20,-296.87,1.21,-350.73,1.19,-315.41,1.76,-1186.95,1.77,-1194.35
|
||||
|
||||
|
||||
|
||||
var vals = string.Format("{0:0.00};{1:0.00};{2:0.00};{3:0.00};{4:0.00};{5:0.00};{6:0.00};{7:0.00};{8:0.00};{9:0.00};{10:0.00};{11:0.00};",
|
||||
GetScale(RollMin, RollMax),
|
||||
GetOffset(RollMin, RollMax),
|
||||
GetScale(PitchMin, PitchMax),
|
||||
GetOffset(PitchMin, PitchMax),
|
||||
GetScale(YawMin, YawMax),
|
||||
GetOffset(YawMin, YawMax),
|
||||
GetScale(ThrottleMin, ThrottleMax),
|
||||
GetOffset(ThrottleMin, ThrottleMax),
|
||||
GetScale(AuxMin, AuxMax),
|
||||
GetOffset(AuxMin, AuxMax),
|
||||
GetScale(ModeMin, ModeMax),
|
||||
GetOffset(ModeMin, ModeMax) // this correct?
|
||||
);
|
||||
|
||||
|
||||
sendString("1" + vals);
|
||||
|
||||
IsCalibrating = false;
|
||||
HideWatermarks();
|
||||
|
||||
// save
|
||||
//sendString(WRITE_TO_EEPROM);
|
||||
}
|
||||
|
||||
private void ResetWatermarks()
|
||||
{
|
||||
ThrottleMin = ThrottleMax = Throttle;
|
||||
RollMax = RollMin = Roll;
|
||||
YawMax = YawMin = Yaw;
|
||||
PitchMax = PitchMin = Pitch;
|
||||
AuxMax = AuxMin = Aux;
|
||||
ModeMax = ModeMin = Mode;
|
||||
}
|
||||
|
||||
private void HideWatermarks()
|
||||
{
|
||||
ThrottleMin = ThrottleMax = 0;
|
||||
RollMax = RollMin = 0;
|
||||
YawMax = YawMin = 0;
|
||||
PitchMax = PitchMin = 0;
|
||||
AuxMax = AuxMin = 0;
|
||||
ModeMax = ModeMin = 0;
|
||||
}
|
||||
|
||||
public ICommand StartCalibrationCommand { get; private set; }
|
||||
public ICommand SaveCalibrationCommand { get; private set; }
|
||||
public ICommand CancelCalibrationCommand { get; private set; }
|
||||
|
||||
public int RollMidValue { get; set; }
|
||||
public int PitchMidValue { get; set; }
|
||||
public int YawMidValue { get; set; }
|
||||
|
||||
|
||||
|
||||
public string Name
|
||||
{
|
||||
get { return "Transmitter Channels"; }
|
||||
}
|
||||
|
||||
public void Activate()
|
||||
{
|
||||
IsCalibrating = false;
|
||||
HideWatermarks();
|
||||
sendString(START_UPDATES);
|
||||
}
|
||||
|
||||
public void DeActivate()
|
||||
{
|
||||
sendString(STOP_UPDATES);
|
||||
}
|
||||
|
||||
public event EventHandler updatedByApm;
|
||||
|
||||
public void handleLineOfText(string strRx)
|
||||
{
|
||||
PropertyHelper.PopulatePropsFromUpdate(this, _propsInUpdateOrder, strRx, false);
|
||||
}
|
||||
|
||||
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||
|
||||
#region bindables
|
||||
|
||||
private int _roll;
|
||||
public int Roll
|
||||
{
|
||||
get { return _roll; }
|
||||
set
|
||||
{
|
||||
if (_roll == value) return;
|
||||
_roll = value;
|
||||
FirePropertyChanged("Roll");
|
||||
if (!_isCalibrating) return;
|
||||
|
||||
if (value > RollMax)
|
||||
RollMax = value;
|
||||
if (value < RollMin)
|
||||
RollMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _rollMax;
|
||||
public int RollMax
|
||||
{
|
||||
get { return _rollMax; }
|
||||
set
|
||||
{
|
||||
if (_rollMax == value) return;
|
||||
_rollMax = value;
|
||||
FirePropertyChanged("RollMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _rollMin;
|
||||
public int RollMin
|
||||
{
|
||||
get { return _rollMin; }
|
||||
set
|
||||
{
|
||||
if (_rollMin == value) return;
|
||||
_rollMin = value;
|
||||
FirePropertyChanged("RollMin");
|
||||
}
|
||||
}
|
||||
|
||||
private int _pitch;
|
||||
public int Pitch
|
||||
{
|
||||
get { return _pitch; }
|
||||
set
|
||||
{
|
||||
if (_pitch == value) return;
|
||||
_pitch = value;
|
||||
FirePropertyChanged("Pitch");
|
||||
if (!_isCalibrating) return;
|
||||
|
||||
if (value > PitchMax)
|
||||
PitchMax = value;
|
||||
if (value < PitchMin)
|
||||
PitchMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _pitchMax;
|
||||
public int PitchMax
|
||||
{
|
||||
get { return _pitchMax; }
|
||||
set
|
||||
{
|
||||
if (_pitchMax == value) return;
|
||||
_pitchMax = value;
|
||||
FirePropertyChanged("PitchMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _pitchMin;
|
||||
public int PitchMin
|
||||
{
|
||||
get { return _pitchMin; }
|
||||
set
|
||||
{
|
||||
if (_pitchMin == value) return;
|
||||
_pitchMin = value;
|
||||
FirePropertyChanged("PitchMin");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private int _yaw;
|
||||
public int Yaw
|
||||
{
|
||||
get { return _yaw; }
|
||||
set
|
||||
{
|
||||
if (_yaw == value) return;
|
||||
_yaw = value;
|
||||
FirePropertyChanged("Yaw");
|
||||
if (!_isCalibrating) return;
|
||||
|
||||
if (value > YawMax)
|
||||
YawMax = value;
|
||||
if (value < YawMin)
|
||||
YawMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _yawMax;
|
||||
public int YawMax
|
||||
{
|
||||
get { return _yawMax; }
|
||||
set
|
||||
{
|
||||
if (_yawMax == value) return;
|
||||
_yawMax = value;
|
||||
FirePropertyChanged("YawMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _yawMin;
|
||||
public int YawMin
|
||||
{
|
||||
get { return _yawMin; }
|
||||
set
|
||||
{
|
||||
if (_yawMin == value) return;
|
||||
_yawMin = value;
|
||||
FirePropertyChanged("YawMin");
|
||||
}
|
||||
}
|
||||
|
||||
private int _throttle;
|
||||
public int Throttle
|
||||
{
|
||||
get { return _throttle; }
|
||||
set
|
||||
{
|
||||
if (_throttle == value) return;
|
||||
_throttle = value;
|
||||
FirePropertyChanged("Throttle");
|
||||
if (!_isCalibrating) return;
|
||||
if (value > ThrottleMax)
|
||||
ThrottleMax = value;
|
||||
if (value < ThrottleMin)
|
||||
ThrottleMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _throttleMin;
|
||||
public int ThrottleMin
|
||||
{
|
||||
get { return _throttleMin; }
|
||||
set
|
||||
{
|
||||
if (_throttleMin == value) return;
|
||||
_throttleMin = value;
|
||||
FirePropertyChanged("ThrottleMin");
|
||||
}
|
||||
}
|
||||
|
||||
private int _throttleMax;
|
||||
public int ThrottleMax
|
||||
{
|
||||
get { return _throttleMax; }
|
||||
set
|
||||
{
|
||||
if (_throttleMax == value) return;
|
||||
_throttleMax = value;
|
||||
FirePropertyChanged("ThrottleMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _mode;
|
||||
public int Mode
|
||||
{
|
||||
get { return _mode; }
|
||||
set
|
||||
{
|
||||
if (_mode == value) return;
|
||||
_mode = value;
|
||||
FirePropertyChanged("Mode");
|
||||
if (!_isCalibrating) return;
|
||||
if (value > ModeMax)
|
||||
ModeMax = value;
|
||||
if (value < ModeMin)
|
||||
ModeMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _modeMax;
|
||||
public int ModeMax
|
||||
{
|
||||
get { return _modeMax; }
|
||||
set
|
||||
{
|
||||
if (_modeMax == value) return;
|
||||
_modeMax = value;
|
||||
FirePropertyChanged("ModeMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _modeMin;
|
||||
public int ModeMin
|
||||
{
|
||||
get { return _modeMin; }
|
||||
set
|
||||
{
|
||||
if (_modeMin == value) return;
|
||||
_modeMin = value;
|
||||
FirePropertyChanged("ModeMin");
|
||||
}
|
||||
}
|
||||
|
||||
private int _aux;
|
||||
public int Aux
|
||||
{
|
||||
get { return _aux; }
|
||||
set
|
||||
{
|
||||
if (_aux == value) return;
|
||||
_aux = value;
|
||||
FirePropertyChanged("Aux");
|
||||
if (!_isCalibrating) return;
|
||||
|
||||
if (value > AuxMax)
|
||||
AuxMax = value;
|
||||
if (value < AuxMin)
|
||||
AuxMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _auxMax;
|
||||
public int AuxMax
|
||||
{
|
||||
get { return _auxMax; }
|
||||
set
|
||||
{
|
||||
if (_auxMax == value) return;
|
||||
_auxMax = value;
|
||||
FirePropertyChanged("AuxMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _auxMin;
|
||||
|
||||
public int AuxMin
|
||||
{
|
||||
get { return _auxMin; }
|
||||
set
|
||||
{
|
||||
if (_auxMin == value) return;
|
||||
_auxMin = value;
|
||||
FirePropertyChanged("AuxMin");
|
||||
}
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,112 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
|
||||
public interface ISupportsExternalInvokedInpc
|
||||
{
|
||||
void FirePropertyChanged(string propName);
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Helper class that takes an update from the APM and writes to properties of an object using reflection
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// The APM gives us a stream of values .eg 4.0,5.2,3.4 etc
|
||||
/// They are in a certain known order, e.g pitch P, pitch I, pitch D... etc
|
||||
///
|
||||
/// instead of having specific value assignment logic in every class to pick
|
||||
/// apart the update and populate properties, this guy will Set the properties
|
||||
/// in the correct order. All the interested class needs to provide is the
|
||||
/// list of property names in the same order as the update from the APMwl
|
||||
/// </remarks>
|
||||
public static class PropertyHelper
|
||||
{
|
||||
// Common method for creating the update data
|
||||
// sentence sent to APM is the commandChar followed by the property
|
||||
// vals in the correct order, seperated by semicolons
|
||||
public static string ComposePropValuesWithCommand(object obj, IList<string> propertiesToUpdate, string commandChar)
|
||||
{
|
||||
var strings = new string[propertiesToUpdate.Count];
|
||||
for (int i = 0; i < propertiesToUpdate.Count; i++)
|
||||
{
|
||||
var prop = obj.GetType().GetProperty(propertiesToUpdate[i]);
|
||||
|
||||
if (prop.PropertyType == typeof(bool))
|
||||
strings[i] = ((bool)prop.GetValue(obj, null)) ? "1" : "0";
|
||||
else
|
||||
strings[i] = prop.GetValue(obj, null).ToString(); // Todo: culture aware strings for floats etc
|
||||
}
|
||||
|
||||
return commandChar + string.Join(";", strings);
|
||||
}
|
||||
|
||||
// Common method for populating properties, using a hardcoded
|
||||
// property update order, and reflection to get the property type
|
||||
public static void PopulatePropsFromUpdate(ISupportsExternalInvokedInpc obj,IList<string> propertiesToUpdate, string strRx, bool fireInpc)
|
||||
{
|
||||
var strs = strRx.Split(',');
|
||||
|
||||
if (propertiesToUpdate.Count != strs.Length)
|
||||
{
|
||||
Console.WriteLine("Processing update with " + strs.Length
|
||||
+ " values, but have " + propertiesToUpdate.Count
|
||||
+ " properties to populate. Ignoring this update");
|
||||
return;
|
||||
}
|
||||
|
||||
for (int i = 0; i < propertiesToUpdate.Count; i++)
|
||||
{
|
||||
var prop = obj.GetType().GetProperty(propertiesToUpdate[i]);
|
||||
var s = strs[i];
|
||||
object value = null;
|
||||
|
||||
if (prop == null)
|
||||
{
|
||||
Console.WriteLine("Trying to set non existant property: " + propertiesToUpdate[i]);
|
||||
break;
|
||||
}
|
||||
|
||||
if (prop.PropertyType == typeof(float))
|
||||
{
|
||||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing float: '{0}', VM: {1}" ,s, obj);
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
}
|
||||
if (prop.PropertyType == typeof(bool))
|
||||
{
|
||||
float val;
|
||||
if (!float.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing float (bool): '{0}', VM: {1}" ,s, obj);
|
||||
break;
|
||||
}
|
||||
value = val != 0.0;
|
||||
}
|
||||
|
||||
if (prop.PropertyType == typeof(int))
|
||||
{
|
||||
int val;
|
||||
if (!int.TryParse(s, out val))
|
||||
{
|
||||
Console.WriteLine("Error parsing int: '{0}', VM: {1}" ,s, obj);
|
||||
break;
|
||||
}
|
||||
value = val;
|
||||
}
|
||||
|
||||
prop.SetValue(obj, value, null);
|
||||
|
||||
if (fireInpc)
|
||||
obj.FirePropertyChanged(propertiesToUpdate[i]);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
@ -1,36 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
static class Program
|
||||
{
|
||||
public static bool IsMonoRuntime;
|
||||
|
||||
/// <summary>
|
||||
/// The main entry point for the application.
|
||||
/// </summary>
|
||||
[STAThread]
|
||||
static void Main()
|
||||
{
|
||||
Application.EnableVisualStyles();
|
||||
Application.SetCompatibleTextRenderingDefault(false);
|
||||
|
||||
var t = Type.GetType("Mono.Runtime");
|
||||
IsMonoRuntime = (t != null);
|
||||
|
||||
var session = new CommsSession();
|
||||
//var session = new FakeCommsSession();
|
||||
|
||||
|
||||
var mainVm = new MainVm(session);
|
||||
|
||||
|
||||
Application.Run(new mainForm(mainVm));
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,36 +0,0 @@
|
||||
using System.Reflection;
|
||||
using System.Runtime.CompilerServices;
|
||||
using System.Runtime.InteropServices;
|
||||
|
||||
// General Information about an assembly is controlled through the following
|
||||
// set of attributes. Change these attribute values to modify the information
|
||||
// associated with an assembly.
|
||||
[assembly: AssemblyTitle("ArducopterConfigurator")]
|
||||
[assembly: AssemblyDescription("")]
|
||||
[assembly: AssemblyConfiguration("")]
|
||||
[assembly: AssemblyCompany("")]
|
||||
[assembly: AssemblyProduct("ArducopterConfigurator")]
|
||||
[assembly: AssemblyCopyright("")]
|
||||
[assembly: AssemblyTrademark("")]
|
||||
[assembly: AssemblyCulture("")]
|
||||
|
||||
// Setting ComVisible to false makes the types in this assembly not visible
|
||||
// to COM components. If you need to access a type in this assembly from
|
||||
// COM, set the ComVisible attribute to true on that type.
|
||||
[assembly: ComVisible(false)]
|
||||
|
||||
// The following GUID is for the ID of the typelib if this project is exposed to COM
|
||||
[assembly: Guid("4bba5a30-abac-4fe7-8e48-84c668f09753")]
|
||||
|
||||
// Version information for an assembly consists of the following four values:
|
||||
//
|
||||
// Major Version
|
||||
// Minor Version
|
||||
// Build Number
|
||||
// Revision
|
||||
//
|
||||
// You can specify all the values or you can default the Build and Revision Numbers
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("0.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.0.0.0")]
|
@ -1,10 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!--
|
||||
This file is automatically generated by Visual Studio .Net. It is
|
||||
used to store generic object data source configuration information.
|
||||
Renaming the file extension or editing the content of this file may
|
||||
cause the file to be unrecognizable by the program.
|
||||
-->
|
||||
<GenericObjectDataSource DisplayName="AcroModeConfigVm" Version="1.0" xmlns="urn:schemas-microsoft-com:xml-msdatasource">
|
||||
<TypeInfo>ArducopterConfigurator.PresentationModels.AcroModeConfigVm, ArducopterConfigurator, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</TypeInfo>
|
||||
</GenericObjectDataSource>
|
@ -1,10 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!--
|
||||
This file is automatically generated by Visual Studio .Net. It is
|
||||
used to store generic object data source configuration information.
|
||||
Renaming the file extension or editing the content of this file may
|
||||
cause the file to be unrecognizable by the program.
|
||||
-->
|
||||
<GenericObjectDataSource DisplayName="FlightDataVm" Version="1.0" xmlns="urn:schemas-microsoft-com:xml-msdatasource">
|
||||
<TypeInfo>ArducopterConfigurator.PresentationModels.FlightDataVm, ArducopterConfigurator, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</TypeInfo>
|
||||
</GenericObjectDataSource>
|
@ -1,10 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!--
|
||||
This file is automatically generated by Visual Studio .Net. It is
|
||||
used to store generic object data source configuration information.
|
||||
Renaming the file extension or editing the content of this file may
|
||||
cause the file to be unrecognizable by the program.
|
||||
-->
|
||||
<GenericObjectDataSource DisplayName="MainVm" Version="1.0" xmlns="urn:schemas-microsoft-com:xml-msdatasource">
|
||||
<TypeInfo>ArducopterConfigurator.PresentationModels.MainVm, ArducopterConfigurator, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</TypeInfo>
|
||||
</GenericObjectDataSource>
|
@ -1,10 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!--
|
||||
This file is automatically generated by Visual Studio .Net. It is
|
||||
used to store generic object data source configuration information.
|
||||
Renaming the file extension or editing the content of this file may
|
||||
cause the file to be unrecognizable by the program.
|
||||
-->
|
||||
<GenericObjectDataSource DisplayName="StableModeConfigVm" Version="1.0" xmlns="urn:schemas-microsoft-com:xml-msdatasource">
|
||||
<TypeInfo>ArducopterConfigurator.PresentationModels.StableModeConfigVm, ArducopterConfigurator, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</TypeInfo>
|
||||
</GenericObjectDataSource>
|
@ -1,10 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!--
|
||||
This file is automatically generated by Visual Studio .Net. It is
|
||||
used to store generic object data source configuration information.
|
||||
Renaming the file extension or editing the content of this file may
|
||||
cause the file to be unrecognizable by the program.
|
||||
-->
|
||||
<GenericObjectDataSource DisplayName="SerialMonitorVm" Version="1.0" xmlns="urn:schemas-microsoft-com:xml-msdatasource">
|
||||
<TypeInfo>ArducopterConfigurator.PresentationModels.SerialMonitorVm, ArducopterConfigurator, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</TypeInfo>
|
||||
</GenericObjectDataSource>
|
@ -1,71 +0,0 @@
|
||||
//------------------------------------------------------------------------------
|
||||
// <auto-generated>
|
||||
// This code was generated by a tool.
|
||||
// Runtime Version:2.0.50727.4952
|
||||
//
|
||||
// Changes to this file may cause incorrect behavior and will be lost if
|
||||
// the code is regenerated.
|
||||
// </auto-generated>
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
namespace ArducopterConfigurator.Properties
|
||||
{
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// A strongly-typed resource class, for looking up localized strings, etc.
|
||||
/// </summary>
|
||||
// This class was auto-generated by the StronglyTypedResourceBuilder
|
||||
// class via a tool like ResGen or Visual Studio.
|
||||
// To add or remove a member, edit your .ResX file then rerun ResGen
|
||||
// with the /str option, or rebuild your VS project.
|
||||
[global::System.CodeDom.Compiler.GeneratedCodeAttribute("System.Resources.Tools.StronglyTypedResourceBuilder", "2.0.0.0")]
|
||||
[global::System.Diagnostics.DebuggerNonUserCodeAttribute()]
|
||||
[global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()]
|
||||
internal class Resources
|
||||
{
|
||||
|
||||
private static global::System.Resources.ResourceManager resourceMan;
|
||||
|
||||
private static global::System.Globalization.CultureInfo resourceCulture;
|
||||
|
||||
[global::System.Diagnostics.CodeAnalysis.SuppressMessageAttribute("Microsoft.Performance", "CA1811:AvoidUncalledPrivateCode")]
|
||||
internal Resources()
|
||||
{
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Returns the cached ResourceManager instance used by this class.
|
||||
/// </summary>
|
||||
[global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)]
|
||||
internal static global::System.Resources.ResourceManager ResourceManager
|
||||
{
|
||||
get
|
||||
{
|
||||
if ((resourceMan == null))
|
||||
{
|
||||
global::System.Resources.ResourceManager temp = new global::System.Resources.ResourceManager("ArducopterConfigurator.Properties.Resources", typeof(Resources).Assembly);
|
||||
resourceMan = temp;
|
||||
}
|
||||
return resourceMan;
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Overrides the current thread's CurrentUICulture property for all
|
||||
/// resource lookups using this strongly typed resource class.
|
||||
/// </summary>
|
||||
[global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)]
|
||||
internal static global::System.Globalization.CultureInfo Culture
|
||||
{
|
||||
get
|
||||
{
|
||||
return resourceCulture;
|
||||
}
|
||||
set
|
||||
{
|
||||
resourceCulture = value;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -1,117 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
@ -1,30 +0,0 @@
|
||||
//------------------------------------------------------------------------------
|
||||
// <auto-generated>
|
||||
// This code was generated by a tool.
|
||||
// Runtime Version:2.0.50727.4952
|
||||
//
|
||||
// Changes to this file may cause incorrect behavior and will be lost if
|
||||
// the code is regenerated.
|
||||
// </auto-generated>
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
namespace ArducopterConfigurator.Properties
|
||||
{
|
||||
|
||||
|
||||
[global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()]
|
||||
[global::System.CodeDom.Compiler.GeneratedCodeAttribute("Microsoft.VisualStudio.Editors.SettingsDesigner.SettingsSingleFileGenerator", "9.0.0.0")]
|
||||
internal sealed partial class Settings : global::System.Configuration.ApplicationSettingsBase
|
||||
{
|
||||
|
||||
private static Settings defaultInstance = ((Settings)(global::System.Configuration.ApplicationSettingsBase.Synchronized(new Settings())));
|
||||
|
||||
public static Settings Default
|
||||
{
|
||||
get
|
||||
{
|
||||
return defaultInstance;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -1,7 +0,0 @@
|
||||
<?xml version='1.0' encoding='utf-8'?>
|
||||
<SettingsFile xmlns="http://schemas.microsoft.com/VisualStudio/2004/01/settings" CurrentProfile="(Default)">
|
||||
<Profiles>
|
||||
<Profile Name="(Default)" />
|
||||
</Profiles>
|
||||
<Settings />
|
||||
</SettingsFile>
|
@ -1,3 +0,0 @@
|
||||
'Misc Tools' Icon from here:
|
||||
http://www.iconarchive.com/show/phuzion-icons-by-kyo-tux/Misc-Tools-icon.html
|
||||
|
@ -1,105 +0,0 @@
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
/// <summary>
|
||||
/// This is a custom tweaking of the standard Progress bar
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
///
|
||||
/// </remarks>
|
||||
[ToolboxBitmap(typeof(ProgressBar))]
|
||||
public class SensorDisplay : ProgressBar
|
||||
{
|
||||
private bool m_IsVertical;
|
||||
private int m_Offset;
|
||||
|
||||
protected override CreateParams CreateParams
|
||||
{
|
||||
get
|
||||
{
|
||||
CreateParams cp = base.CreateParams;
|
||||
if (m_IsVertical)
|
||||
cp.Style |= 0x04;
|
||||
return cp;
|
||||
}
|
||||
}
|
||||
|
||||
public new int Value {
|
||||
get
|
||||
{
|
||||
return base.Value - m_Offset;
|
||||
}
|
||||
set
|
||||
{
|
||||
base.Value = value + m_Offset;
|
||||
}
|
||||
}
|
||||
|
||||
public new int Maximum
|
||||
{
|
||||
get
|
||||
{
|
||||
return base.Maximum - m_Offset;
|
||||
}
|
||||
set
|
||||
{
|
||||
base.Maximum = value + m_Offset;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public new int Minimum
|
||||
{
|
||||
get
|
||||
{
|
||||
return base.Minimum - m_Offset;
|
||||
}
|
||||
set
|
||||
{
|
||||
base.Minimum = value + m_Offset;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
[Description("Whether the display grows vertically")]
|
||||
[Category("SensorDisplay")]
|
||||
[DefaultValue(false)]
|
||||
[RefreshProperties(RefreshProperties.All)]
|
||||
public bool IsVertical
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_IsVertical;
|
||||
}
|
||||
set
|
||||
{
|
||||
m_IsVertical = value;
|
||||
Invalidate();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
[Description("An offset that will be added to every value applied")]
|
||||
[Category("SensorDisplay")]
|
||||
[DefaultValue(0)]
|
||||
[RefreshProperties(RefreshProperties.All)]
|
||||
public int Offset
|
||||
{
|
||||
get
|
||||
{
|
||||
return m_Offset;
|
||||
}
|
||||
set
|
||||
{
|
||||
m_Offset = value;
|
||||
Invalidate();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,126 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="verticalProgressBar1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<metadata name="$this.TrayLargeIcon" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<value>False</value>
|
||||
</metadata>
|
||||
</root>
|
@ -1,43 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
//namespace ArducopterConfiguratorTest
|
||||
//{
|
||||
// [TestFixture]
|
||||
// public class AcroModeConfigVmTest : VmTestBase<AcroModeConfigVm>
|
||||
// {
|
||||
// [SetUp]
|
||||
// public void Setup()
|
||||
// {
|
||||
// sampleLineOfData = "1.950,0.100,0.200,1.950,0.300,0.400,3.200,0.500,0.600,0.320";
|
||||
// getCommand = "P";
|
||||
// setCommand = "O";
|
||||
//
|
||||
// _mockComms = new MockComms();
|
||||
// _mockComms.Connect();
|
||||
// _vm = new AcroModeConfigVm(_mockComms);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void UpdateStringSentIsCorrect()
|
||||
// {
|
||||
// _vm.PitchP = 1.0F;
|
||||
// _vm.PitchI = 2.0F;
|
||||
// _vm.PitchD = 3.0F;
|
||||
// _vm.RollP = 5.0F;
|
||||
// _vm.RollI = 6.0F;
|
||||
// _vm.RollD = 7.0F;
|
||||
// _vm.YawP = 8.0F;
|
||||
// _vm.YawI = 9.0F;
|
||||
// _vm.YawD = 10.0F;
|
||||
// _vm.TransmitterFactor = 4.0F;
|
||||
//
|
||||
// _vm.UpdateCommand.Execute(null);
|
||||
//
|
||||
// Assert.AreEqual(1, _mockComms.SentItems.Count);
|
||||
// Assert.AreEqual("O5;6;7;1;2;3;8;9;10;4", _mockComms.SentItems[0]);
|
||||
// }
|
||||
// }
|
||||
|
||||
|
||||
//}
|
@ -1,53 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
// [TestFixture]
|
||||
// public class AltitudeHoldVmTest : VmTestBase<AltitudeHoldConfigVm>
|
||||
// {
|
||||
//
|
||||
// [SetUp]
|
||||
// public void Setup()
|
||||
// {
|
||||
// sampleLineOfData = "0.800,0.200,0.300";
|
||||
// getCommand = "F";
|
||||
// setCommand = "E";
|
||||
//
|
||||
// _mockComms = new MockComms();
|
||||
// _mockComms.Connect();
|
||||
// _vm = new AltitudeHoldConfigVm(_mockComms);
|
||||
// }
|
||||
//
|
||||
//
|
||||
// [Test]
|
||||
// // For whatever reason, for Altitude the properties are sent in P, D ,I
|
||||
// // order, but received in P,I,D order
|
||||
// public void UpdateStringSentIsCorrect()
|
||||
// {
|
||||
// _vm.P = 1.0F;
|
||||
// _vm.I = 2.0F;
|
||||
// _vm.D = 3.0F;
|
||||
//
|
||||
// _vm.UpdateCommand.Execute(null);
|
||||
//
|
||||
// Assert.AreEqual(1, _mockComms.SentItems.Count);
|
||||
// Assert.AreEqual("E1;3;2", _mockComms.SentItems[0]);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// // For whatever reason, for Altitude the properties are sent in P, D ,I
|
||||
// // order, but received in P,I,D order
|
||||
// public void UpdateStringReceivedPopulatesValuesCorrectly()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// _mockComms.FireLineRecieve(sampleLineOfData);
|
||||
//
|
||||
// Assert.AreEqual(0.8f, _vm.P);
|
||||
// Assert.AreEqual(0.2f, _vm.I);
|
||||
// Assert.AreEqual(0.3f, _vm.D);
|
||||
// }
|
||||
//
|
||||
//
|
||||
// }
|
||||
}
|
@ -1,70 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="3.5" DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<PropertyGroup>
|
||||
<Configuration Condition=" '$(Configuration)' == '' ">Debug</Configuration>
|
||||
<Platform Condition=" '$(Platform)' == '' ">AnyCPU</Platform>
|
||||
<ProductVersion>9.0.30729</ProductVersion>
|
||||
<SchemaVersion>2.0</SchemaVersion>
|
||||
<ProjectGuid>{36B62E9F-668C-45BF-AD72-CFF0C0A65898}</ProjectGuid>
|
||||
<OutputType>Library</OutputType>
|
||||
<AppDesignerFolder>Properties</AppDesignerFolder>
|
||||
<RootNamespace>ArducopterConfiguratorTest</RootNamespace>
|
||||
<AssemblyName>ArducopterConfiguratorTest</AssemblyName>
|
||||
<TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Debug|AnyCPU' ">
|
||||
<DebugSymbols>true</DebugSymbols>
|
||||
<DebugType>full</DebugType>
|
||||
<Optimize>false</Optimize>
|
||||
<OutputPath>bin\Debug\</OutputPath>
|
||||
<DefineConstants>DEBUG;TRACE</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|AnyCPU' ">
|
||||
<DebugType>pdbonly</DebugType>
|
||||
<Optimize>true</Optimize>
|
||||
<OutputPath>bin\Release\</OutputPath>
|
||||
<DefineConstants>TRACE</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
</PropertyGroup>
|
||||
<ItemGroup>
|
||||
<Reference Include="System" />
|
||||
<Reference Include="System.Data" />
|
||||
<Reference Include="System.Xml" />
|
||||
<Reference Include="nunit.framework, Version=2.5.9.10348, Culture=neutral, PublicKeyToken=96d09a1eb7f44a77">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>..\Lib3\nunit.framework.dll</HintPath>
|
||||
</Reference>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Compile Include="AcroModeConfigVmTest.cs" />
|
||||
<Compile Include="AltitudeHoldVmTest.cs" />
|
||||
<Compile Include="CalibrationOffsetsDataVmTest.cs" />
|
||||
<Compile Include="MainVmTests.cs" />
|
||||
<Compile Include="MockComms.cs" />
|
||||
<Compile Include="MotorCommandsVmTest.cs" />
|
||||
<Compile Include="PositionHoldConfigVmTest.cs" />
|
||||
<Compile Include="Properties\AssemblyInfo.cs" />
|
||||
<Compile Include="StableModeConfigVmTest.cs" />
|
||||
<Compile Include="TransmitterChannelsVmTests.cs" />
|
||||
<Compile Include="VmTestBase.cs" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ProjectReference Include="..\ArducopterConfigurator.csproj">
|
||||
<Project>{AF26391C-7E45-4401-8984-96139A67FF31}</Project>
|
||||
<Name>ArducopterConfigurator</Name>
|
||||
</ProjectReference>
|
||||
</ItemGroup>
|
||||
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
|
||||
<Import Project="$(MSBuildBinPath)\Microsoft.CSharp.targets" />
|
||||
<!-- To modify your build process, add your task inside one of the targets below and uncomment it.
|
||||
Other similar extension points exist, see Microsoft.Common.targets.
|
||||
<Target Name="BeforeBuild">
|
||||
</Target>
|
||||
<Target Name="AfterBuild">
|
||||
</Target>
|
||||
-->
|
||||
</Project>
|
@ -1,23 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
// [TestFixture]
|
||||
// public class CalibrationOffsetsDataVmTest : VmTestBase<CalibrationOffsetsDataVm>
|
||||
// {
|
||||
//
|
||||
// [SetUp]
|
||||
// public void Setup()
|
||||
// {
|
||||
// sampleLineOfData = "0.100,0.200,0.300,0.400,0.500,0.600";
|
||||
// getCommand = "J";
|
||||
// setCommand = "I";
|
||||
//
|
||||
// _mockComms = new MockComms();
|
||||
// _mockComms.Connect();
|
||||
// _vm = new CalibrationOffsetsDataVm(_mockComms);
|
||||
// }
|
||||
//
|
||||
// }
|
||||
}
|
@ -1,29 +0,0 @@
|
||||
using System.Text;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
[TestFixture]
|
||||
public class MainVmTests
|
||||
{
|
||||
private MockComms _mockComms;
|
||||
private MainVm _vm;
|
||||
|
||||
[SetUp]
|
||||
public void Setup()
|
||||
{
|
||||
_mockComms = new MockComms();
|
||||
_vm = new MainVm(_mockComms);
|
||||
}
|
||||
|
||||
[Test]
|
||||
public void StateInitiallyDisconnected()
|
||||
{
|
||||
Assert.AreEqual(MainVm.SessionStates.Disconnected, _vm.ConnectionState);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
@ -1,53 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using ArducopterConfigurator;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
public class MockComms : IComms
|
||||
{
|
||||
public event Action<string> LineOfDataReceived;
|
||||
public string CommPort { get; set; }
|
||||
public List<string> SentItems = new List<string>();
|
||||
private bool _isConnected;
|
||||
|
||||
public bool IsConnected
|
||||
{
|
||||
get { return _isConnected; }
|
||||
}
|
||||
|
||||
public int BaudRate
|
||||
{
|
||||
get { throw new System.NotImplementedException(); }
|
||||
set { throw new System.NotImplementedException(); }
|
||||
}
|
||||
|
||||
public IEnumerable<string> ListCommPorts()
|
||||
{
|
||||
return new[] {"MockComport1"};
|
||||
}
|
||||
|
||||
public void Send(string send)
|
||||
{
|
||||
SentItems.Add(send);
|
||||
}
|
||||
|
||||
public bool Connect()
|
||||
{
|
||||
_isConnected = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool DisConnect()
|
||||
{
|
||||
_isConnected = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
public void FireLineRecieve(string s)
|
||||
{
|
||||
if (LineOfDataReceived != null)
|
||||
LineOfDataReceived(s);
|
||||
}
|
||||
}
|
||||
}
|
@ -1,26 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
[TestFixture]
|
||||
public class MotorCommandsVmTest
|
||||
{
|
||||
private MockComms _mockComms;
|
||||
private MotorCommandsVm _vm;
|
||||
|
||||
[SetUp]
|
||||
public void Setup()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
// Todo
|
||||
// test that it stops all motors on deactivate
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,23 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
// [TestFixture]
|
||||
// public class PositionHoldConfigVmTest : VmTestBase<PositionHoldConfigVm>
|
||||
// {
|
||||
//
|
||||
// [SetUp]
|
||||
// public void Setup()
|
||||
// {
|
||||
// sampleLineOfData = "0.015,0.005,0.010,0.015,0.005,0.010,22.000,0.870";
|
||||
// getCommand = "D";
|
||||
// setCommand = "C";
|
||||
//
|
||||
// _mockComms = new MockComms();
|
||||
// _mockComms.Connect();
|
||||
// _vm = new PositionHoldConfigVm(_mockComms);
|
||||
// }
|
||||
//
|
||||
// }
|
||||
}
|
@ -1,36 +0,0 @@
|
||||
using System.Reflection;
|
||||
using System.Runtime.CompilerServices;
|
||||
using System.Runtime.InteropServices;
|
||||
|
||||
// General Information about an assembly is controlled through the following
|
||||
// set of attributes. Change these attribute values to modify the information
|
||||
// associated with an assembly.
|
||||
[assembly: AssemblyTitle("ArducopterConfiguratorTest")]
|
||||
[assembly: AssemblyDescription("")]
|
||||
[assembly: AssemblyConfiguration("")]
|
||||
[assembly: AssemblyCompany("TOSHIBA")]
|
||||
[assembly: AssemblyProduct("ArducopterConfiguratorTest")]
|
||||
[assembly: AssemblyCopyright("Copyright © TOSHIBA 2010")]
|
||||
[assembly: AssemblyTrademark("")]
|
||||
[assembly: AssemblyCulture("")]
|
||||
|
||||
// Setting ComVisible to false makes the types in this assembly not visible
|
||||
// to COM components. If you need to access a type in this assembly from
|
||||
// COM, set the ComVisible attribute to true on that type.
|
||||
[assembly: ComVisible(false)]
|
||||
|
||||
// The following GUID is for the ID of the typelib if this project is exposed to COM
|
||||
[assembly: Guid("19d172a3-8241-459a-bee7-3318a20fce16")]
|
||||
|
||||
// Version information for an assembly consists of the following four values:
|
||||
//
|
||||
// Major Version
|
||||
// Minor Version
|
||||
// Build Number
|
||||
// Revision
|
||||
//
|
||||
// You can specify all the values or you can default the Build and Revision Numbers
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.0.0.0")]
|
@ -1,75 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
// [TestFixture]
|
||||
// public class StableModeConfigVmTest : VmTestBase<StableModeConfigVm>
|
||||
// {
|
||||
//
|
||||
// [SetUp]
|
||||
// public void Setup()
|
||||
// {
|
||||
// sampleLineOfData = "1.950,0.100,0.200,1.950,0.300,0.400,3.200,0.500,0.600,0.320,1.00";
|
||||
// getCommand = "B";
|
||||
// setCommand = "A";
|
||||
//
|
||||
// _mockComms = new MockComms();
|
||||
// _mockComms.Connect();
|
||||
// _vm = new StableModeConfigVm(_mockComms);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void UpdateStringSentIsCorrect()
|
||||
// {
|
||||
// _vm.PitchP = 1.0F;
|
||||
// _vm.PitchI = 2.0F;
|
||||
// _vm.PitchD = 3.0F;
|
||||
// _vm.RollP = 5.0F;
|
||||
// _vm.RollI = 6.0F;
|
||||
// _vm.RollD = 7.0F;
|
||||
// _vm.YawP = 8.0F;
|
||||
// _vm.YawI = 9.0F;
|
||||
// _vm.YawD = 10.0F;
|
||||
// _vm.MagnetometerEnable = true;
|
||||
// _vm.KPrate = 4.0F;
|
||||
//
|
||||
// _vm.UpdateCommand.Execute(null);
|
||||
//
|
||||
//
|
||||
// Assert.AreEqual(1, _mockComms.SentItems.Count);
|
||||
//
|
||||
// //A[KP Quad Roll];[KI Quad Roll];[KP RATE ROLL];
|
||||
// // [KP Quad Pitch];[KI Quad Pitch];[KP RATE PITCH];
|
||||
// // [KP Quad Yaw];[KI Quad Yaw];[KP Rate Yaw];
|
||||
// // [KP Rate];[Magneto]
|
||||
// Assert.AreEqual("A5;6;7;1;2;3;8;9;10;4;1", _mockComms.SentItems[0]);
|
||||
// }
|
||||
//
|
||||
//
|
||||
//
|
||||
// [Test]
|
||||
// public void UpdateStringReceivedPopulatesValuesCorrectly()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// _mockComms.FireLineRecieve(sampleLineOfData);
|
||||
//
|
||||
// Assert.AreEqual(1.95f, _vm.RollP);
|
||||
// Assert.AreEqual(0.1f, _vm.RollI);
|
||||
// Assert.AreEqual(0.2f, _vm.RollD);
|
||||
//
|
||||
// Assert.AreEqual(1.95f, _vm.PitchP);
|
||||
// Assert.AreEqual(0.3f, _vm.PitchI);
|
||||
// Assert.AreEqual(0.4f, _vm.PitchD);
|
||||
//
|
||||
// Assert.AreEqual(3.2f, _vm.YawP);
|
||||
// Assert.AreEqual(0.5f, _vm.YawI);
|
||||
// Assert.AreEqual(0.6f, _vm.YawD);
|
||||
//
|
||||
// Assert.AreEqual(0.32f, _vm.KPrate);
|
||||
//
|
||||
// Assert.AreEqual(true, _vm.MagnetometerEnable);
|
||||
//
|
||||
// }
|
||||
// }
|
||||
}
|
@ -1,87 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
// [TestFixture]
|
||||
// public class TransmitterChannelsVmTests
|
||||
// {
|
||||
// private MockComms _mockComms;
|
||||
// private TransmitterChannelsVm _vm;
|
||||
//
|
||||
// [SetUp]
|
||||
// public void Setup()
|
||||
// {
|
||||
// _mockComms = new MockComms();
|
||||
// _mockComms.Connect();
|
||||
// _vm = new TransmitterChannelsVm(_mockComms);
|
||||
//
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void SendsCorrectCommandOnActivate()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// Assert.AreEqual(1,_mockComms.SentItems.Count);
|
||||
// Assert.AreEqual("U",_mockComms.SentItems[0]);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void SendsCorrectCommandOnDeActivate()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// _vm.DeActivate();
|
||||
//
|
||||
// Assert.AreEqual(2, _mockComms.SentItems.Count);
|
||||
// Assert.AreEqual("X", _mockComms.SentItems[1]);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void ValuesAreSet()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// // What do the MID values do?
|
||||
// //1403,1620,1523,1501,1900,1950,0,0,0
|
||||
// // Aileron,Elevator,Yaw,Throttle,AUX1 (Mode),AUX2 ,Roll MID value,Pitch MID value,Yaw MID Value
|
||||
//
|
||||
// var sampleData = "1403,1620,1523,1501,1900,1950,0,0,0";
|
||||
// _mockComms.FireLineRecieve(sampleData);
|
||||
// Assert.AreEqual(1403, _vm.Roll);
|
||||
// Assert.AreEqual(1620, _vm.Pitch);
|
||||
// Assert.AreEqual(1523, _vm.Yaw);
|
||||
// Assert.AreEqual(1501, _vm.Throttle);
|
||||
// Assert.AreEqual(1900, _vm.Mode);
|
||||
// Assert.AreEqual(1950, _vm.Aux);
|
||||
// }
|
||||
//
|
||||
//
|
||||
// [Test]
|
||||
// public void MaximumsAndMinimumsAreSet()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// // What do the MID values do?
|
||||
// //1403,1620,1523,1501,1900,1950,0,0,0
|
||||
// // Aileron,Elevator,Yaw,Throttle,AUX1 (Mode),AUX2 ,Roll MID value,Pitch MID value,Yaw MID Value
|
||||
//
|
||||
// var sampleData = "1403,1620,1523,1501,1900,1950,0,0,0";
|
||||
// _mockComms.FireLineRecieve(sampleData);
|
||||
// _vm.ResetCommand.Execute(null);
|
||||
// _mockComms.FireLineRecieve(sampleData);
|
||||
//
|
||||
// Assert.AreEqual(1403,_vm.Roll);
|
||||
// Assert.AreEqual(1403,_vm.RollMin);
|
||||
// Assert.AreEqual(1403,_vm.RollMax);
|
||||
// }
|
||||
//
|
||||
// }
|
||||
}
|
||||
/*
|
||||
roll_slope,ch_roll_offset,
|
||||
ch_pitch_slope,ch_pitch_offset
|
||||
ch_yaw_slope,ch_yaw_offset,
|
||||
ch_throttle_slope,ch_throttle_offset
|
||||
ch_aux_slope,ch_aux_offset
|
||||
ch_aux2_slope,ch_aux2_offset
|
||||
*/
|
||||
// 1.20,-327.73,1.20,-328.92,1.21,-344.66,1.21,-343.83,1.79,-1225.81,1.79,-1227.60
|
||||
|
@ -1,57 +0,0 @@
|
||||
using ArducopterConfigurator;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
// public abstract class VmTestBase<T> where T : MonitorVm
|
||||
// {
|
||||
// protected T _vm;
|
||||
// protected MockComms _mockComms;
|
||||
// protected string sampleLineOfData; // should be taken from a real APM if possible
|
||||
// protected string getCommand;
|
||||
// protected string setCommand;
|
||||
//
|
||||
// [Test]
|
||||
// public void ActivateSendsCorrectCommand()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// Assert.AreEqual(1, _mockComms.SentItems.Count);
|
||||
// Assert.AreEqual(getCommand, _mockComms.SentItems[0]);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void ReceivedDataIgnoredWhenNotActive()
|
||||
// {
|
||||
// bool inpcFired = false;
|
||||
// _vm.PropertyChanged += delegate { inpcFired = true; };
|
||||
//
|
||||
// _mockComms.FireLineRecieve(sampleLineOfData);
|
||||
// Assert.False(inpcFired);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void ReceivedDataIgnoredAfterDeActive()
|
||||
// {
|
||||
// _vm.Activate();
|
||||
// _mockComms.FireLineRecieve(sampleLineOfData);
|
||||
// _vm.DeActivate();
|
||||
// _mockComms.FireLineRecieve(sampleLineOfData);
|
||||
// bool inpcFired = false;
|
||||
// _vm.PropertyChanged += delegate { inpcFired = true; };
|
||||
//
|
||||
// Assert.False(inpcFired);
|
||||
// }
|
||||
//
|
||||
// [Test]
|
||||
// public void UpdateStringReceivedPopulatesValues()
|
||||
// {
|
||||
// bool inpcFired = false;
|
||||
// _vm.PropertyChanged += delegate { inpcFired = true; };
|
||||
//
|
||||
// _vm.Activate();
|
||||
// _mockComms.FireLineRecieve(sampleLineOfData);
|
||||
//
|
||||
// Assert.True(inpcFired);
|
||||
// }
|
||||
// }
|
||||
}
|
@ -1,24 +0,0 @@
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
[Description("Vertical Progress Bar")]
|
||||
[ToolboxBitmap(typeof(ProgressBar))]
|
||||
public class VerticalProgressBar : ProgressBar
|
||||
{
|
||||
protected override CreateParams CreateParams
|
||||
{
|
||||
get
|
||||
{
|
||||
CreateParams cp = base.CreateParams;
|
||||
cp.Style |= 0x04;
|
||||
return cp;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,421 +0,0 @@
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
partial class AcroConfigView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(AcroConfigView));
|
||||
this.button2 = new System.Windows.Forms.Button();
|
||||
this.AcroModeConfigVmBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.groupBox4 = new System.Windows.Forms.GroupBox();
|
||||
this.numericUpDown9 = new System.Windows.Forms.NumericUpDown();
|
||||
this.numericUpDown8 = new System.Windows.Forms.NumericUpDown();
|
||||
this.numericUpDown3 = new System.Windows.Forms.NumericUpDown();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
this.label8 = new System.Windows.Forms.Label();
|
||||
this.label9 = new System.Windows.Forms.Label();
|
||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||
this.numericUpDown7 = new System.Windows.Forms.NumericUpDown();
|
||||
this.numericUpDown6 = new System.Windows.Forms.NumericUpDown();
|
||||
this.numericUpDown2 = new System.Windows.Forms.NumericUpDown();
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
||||
this.numericUpDown5 = new System.Windows.Forms.NumericUpDown();
|
||||
this.numericUpDown4 = new System.Windows.Forms.NumericUpDown();
|
||||
this.numericUpDown1 = new System.Windows.Forms.NumericUpDown();
|
||||
this.label3 = new System.Windows.Forms.Label();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.textBox10 = new System.Windows.Forms.TextBox();
|
||||
this.label10 = new System.Windows.Forms.Label();
|
||||
this.toolTips = new System.Windows.Forms.ToolTip(this.components);
|
||||
((System.ComponentModel.ISupportInitialize)(this.AcroModeConfigVmBindingSource)).BeginInit();
|
||||
this.groupBox4.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown9)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown8)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown3)).BeginInit();
|
||||
this.groupBox2.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown7)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown6)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown2)).BeginInit();
|
||||
this.groupBox3.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown5)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown4)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown1)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// button2
|
||||
//
|
||||
this.button2.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.AcroModeConfigVmBindingSource, "RefreshCommand", true));
|
||||
this.button2.Image = ((System.Drawing.Image)(resources.GetObject("button2.Image")));
|
||||
this.button2.Location = new System.Drawing.Point(235, 108);
|
||||
this.button2.Name = "button2";
|
||||
this.button2.Size = new System.Drawing.Size(26, 26);
|
||||
this.button2.TabIndex = 12;
|
||||
this.button2.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// AcroModeConfigVmBindingSource
|
||||
//
|
||||
this.AcroModeConfigVmBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.AcroModeConfigVm);
|
||||
//
|
||||
// groupBox4
|
||||
//
|
||||
this.groupBox4.Controls.Add(this.numericUpDown9);
|
||||
this.groupBox4.Controls.Add(this.numericUpDown8);
|
||||
this.groupBox4.Controls.Add(this.numericUpDown3);
|
||||
this.groupBox4.Controls.Add(this.label7);
|
||||
this.groupBox4.Controls.Add(this.label8);
|
||||
this.groupBox4.Controls.Add(this.label9);
|
||||
this.groupBox4.Location = new System.Drawing.Point(181, 3);
|
||||
this.groupBox4.Name = "groupBox4";
|
||||
this.groupBox4.Size = new System.Drawing.Size(80, 101);
|
||||
this.groupBox4.TabIndex = 11;
|
||||
this.groupBox4.TabStop = false;
|
||||
this.groupBox4.Text = "Yaw";
|
||||
//
|
||||
// numericUpDown9
|
||||
//
|
||||
this.numericUpDown9.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "YawD", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown9.DecimalPlaces = 2;
|
||||
this.numericUpDown9.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown9.Location = new System.Drawing.Point(23, 71);
|
||||
this.numericUpDown9.Name = "numericUpDown9";
|
||||
this.numericUpDown9.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown9.TabIndex = 17;
|
||||
//
|
||||
// numericUpDown8
|
||||
//
|
||||
this.numericUpDown8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "PitchI", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown8.DecimalPlaces = 2;
|
||||
this.numericUpDown8.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown8.Location = new System.Drawing.Point(23, 45);
|
||||
this.numericUpDown8.Name = "numericUpDown8";
|
||||
this.numericUpDown8.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown8.TabIndex = 16;
|
||||
//
|
||||
// numericUpDown3
|
||||
//
|
||||
this.numericUpDown3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "YawP", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown3.DecimalPlaces = 2;
|
||||
this.numericUpDown3.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown3.Location = new System.Drawing.Point(23, 20);
|
||||
this.numericUpDown3.Name = "numericUpDown3";
|
||||
this.numericUpDown3.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown3.TabIndex = 15;
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(7, 74);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(15, 13);
|
||||
this.label7.TabIndex = 5;
|
||||
this.label7.Text = "D";
|
||||
//
|
||||
// label8
|
||||
//
|
||||
this.label8.AutoSize = true;
|
||||
this.label8.Location = new System.Drawing.Point(7, 48);
|
||||
this.label8.Name = "label8";
|
||||
this.label8.Size = new System.Drawing.Size(10, 13);
|
||||
this.label8.TabIndex = 4;
|
||||
this.label8.Text = "I";
|
||||
//
|
||||
// label9
|
||||
//
|
||||
this.label9.AutoSize = true;
|
||||
this.label9.Location = new System.Drawing.Point(7, 22);
|
||||
this.label9.Name = "label9";
|
||||
this.label9.Size = new System.Drawing.Size(14, 13);
|
||||
this.label9.TabIndex = 3;
|
||||
this.label9.Text = "P";
|
||||
//
|
||||
// groupBox2
|
||||
//
|
||||
this.groupBox2.Controls.Add(this.numericUpDown7);
|
||||
this.groupBox2.Controls.Add(this.numericUpDown6);
|
||||
this.groupBox2.Controls.Add(this.numericUpDown2);
|
||||
this.groupBox2.Controls.Add(this.label4);
|
||||
this.groupBox2.Controls.Add(this.label5);
|
||||
this.groupBox2.Controls.Add(this.label6);
|
||||
this.groupBox2.Location = new System.Drawing.Point(94, 3);
|
||||
this.groupBox2.Name = "groupBox2";
|
||||
this.groupBox2.Size = new System.Drawing.Size(81, 101);
|
||||
this.groupBox2.TabIndex = 10;
|
||||
this.groupBox2.TabStop = false;
|
||||
this.groupBox2.Text = "Pitch";
|
||||
//
|
||||
// numericUpDown7
|
||||
//
|
||||
this.numericUpDown7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "PitchD", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown7.DecimalPlaces = 2;
|
||||
this.numericUpDown7.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown7.Location = new System.Drawing.Point(23, 71);
|
||||
this.numericUpDown7.Name = "numericUpDown7";
|
||||
this.numericUpDown7.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown7.TabIndex = 16;
|
||||
//
|
||||
// numericUpDown6
|
||||
//
|
||||
this.numericUpDown6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "PitchI", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown6.DecimalPlaces = 2;
|
||||
this.numericUpDown6.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown6.Location = new System.Drawing.Point(23, 45);
|
||||
this.numericUpDown6.Name = "numericUpDown6";
|
||||
this.numericUpDown6.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown6.TabIndex = 15;
|
||||
//
|
||||
// numericUpDown2
|
||||
//
|
||||
this.numericUpDown2.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "PitchP", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown2.DecimalPlaces = 2;
|
||||
this.numericUpDown2.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown2.Location = new System.Drawing.Point(23, 19);
|
||||
this.numericUpDown2.Name = "numericUpDown2";
|
||||
this.numericUpDown2.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown2.TabIndex = 14;
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(7, 74);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(15, 13);
|
||||
this.label4.TabIndex = 5;
|
||||
this.label4.Text = "D";
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(7, 48);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(10, 13);
|
||||
this.label5.TabIndex = 4;
|
||||
this.label5.Text = "I";
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(7, 22);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(14, 13);
|
||||
this.label6.TabIndex = 3;
|
||||
this.label6.Text = "P";
|
||||
//
|
||||
// groupBox3
|
||||
//
|
||||
this.groupBox3.Controls.Add(this.numericUpDown5);
|
||||
this.groupBox3.Controls.Add(this.numericUpDown4);
|
||||
this.groupBox3.Controls.Add(this.numericUpDown1);
|
||||
this.groupBox3.Controls.Add(this.label3);
|
||||
this.groupBox3.Controls.Add(this.label2);
|
||||
this.groupBox3.Controls.Add(this.label1);
|
||||
this.groupBox3.Location = new System.Drawing.Point(6, 2);
|
||||
this.groupBox3.Name = "groupBox3";
|
||||
this.groupBox3.Size = new System.Drawing.Size(82, 101);
|
||||
this.groupBox3.TabIndex = 9;
|
||||
this.groupBox3.TabStop = false;
|
||||
this.groupBox3.Text = "Roll";
|
||||
//
|
||||
// numericUpDown5
|
||||
//
|
||||
this.numericUpDown5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "RollD", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown5.DecimalPlaces = 2;
|
||||
this.numericUpDown5.Increment = new decimal(new int[] {
|
||||
25,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown5.Location = new System.Drawing.Point(23, 72);
|
||||
this.numericUpDown5.Name = "numericUpDown5";
|
||||
this.numericUpDown5.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown5.TabIndex = 15;
|
||||
//
|
||||
// numericUpDown4
|
||||
//
|
||||
this.numericUpDown4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "RollI", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown4.DecimalPlaces = 2;
|
||||
this.numericUpDown4.Increment = new decimal(new int[] {
|
||||
25,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown4.Location = new System.Drawing.Point(23, 46);
|
||||
this.numericUpDown4.Name = "numericUpDown4";
|
||||
this.numericUpDown4.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown4.TabIndex = 14;
|
||||
//
|
||||
// numericUpDown1
|
||||
//
|
||||
this.numericUpDown1.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.AcroModeConfigVmBindingSource, "RollP", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.numericUpDown1.DecimalPlaces = 2;
|
||||
this.numericUpDown1.Increment = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
0,
|
||||
131072});
|
||||
this.numericUpDown1.Location = new System.Drawing.Point(23, 20);
|
||||
this.numericUpDown1.Name = "numericUpDown1";
|
||||
this.numericUpDown1.Size = new System.Drawing.Size(50, 20);
|
||||
this.numericUpDown1.TabIndex = 13;
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(7, 74);
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(15, 13);
|
||||
this.label3.TabIndex = 5;
|
||||
this.label3.Text = "D";
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(7, 48);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(10, 13);
|
||||
this.label2.TabIndex = 4;
|
||||
this.label2.Text = "I";
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(7, 22);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(14, 13);
|
||||
this.label1.TabIndex = 3;
|
||||
this.label1.Text = "P";
|
||||
//
|
||||
// textBox10
|
||||
//
|
||||
this.textBox10.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.AcroModeConfigVmBindingSource, "TransmitterFactor", true));
|
||||
this.textBox10.Location = new System.Drawing.Point(64, 112);
|
||||
this.textBox10.Name = "textBox10";
|
||||
this.textBox10.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox10.TabIndex = 6;
|
||||
//
|
||||
// label10
|
||||
//
|
||||
this.label10.AutoSize = true;
|
||||
this.label10.Location = new System.Drawing.Point(7, 114);
|
||||
this.label10.Name = "label10";
|
||||
this.label10.Size = new System.Drawing.Size(55, 13);
|
||||
this.label10.TabIndex = 6;
|
||||
this.label10.Text = "Tx Factor:";
|
||||
this.toolTips.SetToolTip(this.label10, " A higher number will cause a change in a transmitter stick position to have a st" +
|
||||
"ronger effect on the ArduPirate");
|
||||
//
|
||||
// AcroConfigView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.label10);
|
||||
this.Controls.Add(this.textBox10);
|
||||
this.Controls.Add(this.button2);
|
||||
this.Controls.Add(this.groupBox4);
|
||||
this.Controls.Add(this.groupBox2);
|
||||
this.Controls.Add(this.groupBox3);
|
||||
this.Name = "AcroConfigView";
|
||||
this.Size = new System.Drawing.Size(271, 136);
|
||||
((System.ComponentModel.ISupportInitialize)(this.AcroModeConfigVmBindingSource)).EndInit();
|
||||
this.groupBox4.ResumeLayout(false);
|
||||
this.groupBox4.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown9)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown8)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown3)).EndInit();
|
||||
this.groupBox2.ResumeLayout(false);
|
||||
this.groupBox2.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown7)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown6)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown2)).EndInit();
|
||||
this.groupBox3.ResumeLayout(false);
|
||||
this.groupBox3.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown5)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown4)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.numericUpDown1)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.Button button2;
|
||||
private System.Windows.Forms.GroupBox groupBox4;
|
||||
private System.Windows.Forms.Label label7;
|
||||
private System.Windows.Forms.Label label8;
|
||||
private System.Windows.Forms.Label label9;
|
||||
private System.Windows.Forms.GroupBox groupBox2;
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.GroupBox groupBox3;
|
||||
private System.Windows.Forms.Label label3;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private System.Windows.Forms.TextBox textBox10;
|
||||
private System.Windows.Forms.Label label10;
|
||||
private System.Windows.Forms.BindingSource AcroModeConfigVmBindingSource;
|
||||
private System.Windows.Forms.ToolTip toolTips;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown1;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown3;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown2;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown9;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown8;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown7;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown6;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown5;
|
||||
private System.Windows.Forms.NumericUpDown numericUpDown4;
|
||||
}
|
||||
}
|
@ -1,33 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
public partial class AcroConfigView : AcroControlDesignable
|
||||
{
|
||||
public AcroConfigView()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public override void SetDataContext(AcroModeConfigVm vm)
|
||||
{
|
||||
BindButtons(vm);
|
||||
|
||||
AcroModeConfigVmBindingSource.DataSource = vm;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
vm.PropertyChanged += ((sender, e) => AcroModeConfigVmBindingSource.ResetBindings(false));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class AcroControlDesignable : ViewCommon<AcroModeConfigVm> { }
|
||||
}
|
@ -1,146 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="AcroModeConfigVmBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="button2.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAYAAAAf8/9hAAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8
|
||||
YQUAAAAgY0hSTQAAeiYAAICEAAD6AAAAgOgAAHUwAADqYAAAOpgAABdwnLpRPAAAAAlwSFlzAAAOvAAA
|
||||
DrwBlbxySQAAAtVJREFUOE9jYKAaiN/PweB3RIohcL8MGIPYIDFigVbd+cTIeXfuxS+5+yQWiCPn3X4o
|
||||
X3Y2EaRfMOOojkbN2XKprCMGOM2TyDoakrfm3tcZ59/+nw7EnQef/dGqPJnKELhTLHzGtcNzT77+X7Hh
|
||||
wQXdsuOeDAz1TKgGWazktG87M6dx95P/vcde/u8/8ep/4Zo772Sz9tsw+K8X8Oo9N7Nr18PP666+/1+z
|
||||
8d5VsDgykEvZ4ZO/6taHroPP/sfOvHSvZM3tL7EzLt5hcFsuC1ZnPJNLJWtvYenqGx/mnnr1P3jCme0M
|
||||
9vMFoGaksTrVHZxZv/3h/9T5l96IRW/wMyvZU2ZVtnsKg0UvJ8Kiejbjwp2tHTvv/61Ye/OjfPJGD4ic
|
||||
UreYf8ehU9Wb7v33btq/jUG9kxdoIyuDy0x+9AAT8J6rnzD99KvaDXf+qyStLofIq9TLWJbtuBUw5cJ/
|
||||
3fQ10xkYQplxhrRVv7pV1e7ngVPO/5eNWNQIdUGxmHrKmhN61Uf+q8QtWc7AEI8a9xa9Qjy2XcFAi/jE
|
||||
PCdH6RTt/q5Tuve3iNfUZJhFzPKBMybole7/r5G8+j6nfpUZsguEHLvcjNJXPlPwnzZdKXL+CfWSg/81
|
||||
U1c/5bZo0oWrEzCtttNKWvFKK3/3fznfyQe5VHINYV6RcO6q1crd+V8hdfMfhfTt/9Syd/yX8+oHetWY
|
||||
FckiY1YJh+Y6zeS137SydvzXjZ53R8y0KpCBwZVbJWDqVrHEHf/ZInf8F07Y8V/Rf9otVtUsjBTJyMBv
|
||||
LyBmXtqpHTHvk27IlGt8KuFuDCK2RhrB0x4rJW3+LxmzARjym/7rBE99wqkQY47sTUYghx2IxRgY+I04
|
||||
xW3yWHnUUoB8LwYm7ghuOc+pvCoRy3lUIxfzqcUsEFSPamIV1NOB6gHpBQNQ2gaFPi8QCwKxKBBLArEU
|
||||
EEtA+cJAWgCIuaGawfkBAATBFuWVyulDAAAAAElFTkSuQmCC
|
||||
</value>
|
||||
</data>
|
||||
<metadata name="toolTips.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>259, 17</value>
|
||||
</metadata>
|
||||
</root>
|
@ -1,141 +0,0 @@
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
partial class AltitudeHoldConfigView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(AltitudeHoldConfigView));
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.textBox4 = new System.Windows.Forms.TextBox();
|
||||
this.AltitudeHoldConfigBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.textBox5 = new System.Windows.Forms.TextBox();
|
||||
this.textBox6 = new System.Windows.Forms.TextBox();
|
||||
this.button2 = new System.Windows.Forms.Button();
|
||||
((System.ComponentModel.ISupportInitialize)(this.AltitudeHoldConfigBindingSource)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(11, 67);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(15, 13);
|
||||
this.label4.TabIndex = 16;
|
||||
this.label4.Text = "D";
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(11, 41);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(10, 13);
|
||||
this.label5.TabIndex = 15;
|
||||
this.label5.Text = "I";
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(11, 15);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(14, 13);
|
||||
this.label6.TabIndex = 14;
|
||||
this.label6.Text = "P";
|
||||
//
|
||||
// textBox4
|
||||
//
|
||||
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.AltitudeHoldConfigBindingSource, "D", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.textBox4.Location = new System.Drawing.Point(27, 64);
|
||||
this.textBox4.Name = "textBox4";
|
||||
this.textBox4.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox4.TabIndex = 13;
|
||||
//
|
||||
// AltitudeHoldConfigBindingSource
|
||||
//
|
||||
this.AltitudeHoldConfigBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.AltitudeHoldConfigVm);
|
||||
//
|
||||
// textBox5
|
||||
//
|
||||
this.textBox5.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.AltitudeHoldConfigBindingSource, "I", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.textBox5.Location = new System.Drawing.Point(27, 38);
|
||||
this.textBox5.Name = "textBox5";
|
||||
this.textBox5.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox5.TabIndex = 12;
|
||||
//
|
||||
// textBox6
|
||||
//
|
||||
this.textBox6.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.AltitudeHoldConfigBindingSource, "P", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.textBox6.Location = new System.Drawing.Point(27, 12);
|
||||
this.textBox6.Name = "textBox6";
|
||||
this.textBox6.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox6.TabIndex = 11;
|
||||
//
|
||||
// button2
|
||||
//
|
||||
this.button2.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.button2.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.AltitudeHoldConfigBindingSource, "RefreshCommand", true));
|
||||
this.button2.Image = ((System.Drawing.Image)(resources.GetObject("button2.Image")));
|
||||
this.button2.Location = new System.Drawing.Point(185, 60);
|
||||
this.button2.Name = "button2";
|
||||
this.button2.Size = new System.Drawing.Size(26, 26);
|
||||
this.button2.TabIndex = 18;
|
||||
this.button2.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// AltitudeHoldConfigView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.button2);
|
||||
this.Controls.Add(this.label4);
|
||||
this.Controls.Add(this.label5);
|
||||
this.Controls.Add(this.label6);
|
||||
this.Controls.Add(this.textBox4);
|
||||
this.Controls.Add(this.textBox5);
|
||||
this.Controls.Add(this.textBox6);
|
||||
this.Name = "AltitudeHoldConfigView";
|
||||
this.Size = new System.Drawing.Size(260, 98);
|
||||
((System.ComponentModel.ISupportInitialize)(this.AltitudeHoldConfigBindingSource)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.TextBox textBox4;
|
||||
private System.Windows.Forms.TextBox textBox5;
|
||||
private System.Windows.Forms.TextBox textBox6;
|
||||
private System.Windows.Forms.BindingSource AltitudeHoldConfigBindingSource;
|
||||
private System.Windows.Forms.Button button2;
|
||||
|
||||
}
|
||||
}
|
@ -1,33 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
public partial class AltitudeHoldConfigView : AltitudeControlDesignable
|
||||
{
|
||||
public AltitudeHoldConfigView()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
}
|
||||
|
||||
public override void SetDataContext(AltitudeHoldConfigVm vm)
|
||||
{
|
||||
BindButtons(vm);
|
||||
|
||||
AltitudeHoldConfigBindingSource.DataSource = vm;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
vm.PropertyChanged += ((sender, e) => AltitudeHoldConfigBindingSource.ResetBindings(false));
|
||||
}
|
||||
}
|
||||
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class AltitudeControlDesignable : ViewCommon<AltitudeHoldConfigVm> { }
|
||||
}
|
@ -1,143 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="AltitudeHoldConfigBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="button2.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAYAAAAf8/9hAAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8
|
||||
YQUAAAAgY0hSTQAAeiYAAICEAAD6AAAAgOgAAHUwAADqYAAAOpgAABdwnLpRPAAAAAlwSFlzAAAOwQAA
|
||||
DsEBuJFr7QAAAtVJREFUOE9jYKAaiN/PweB3RIohcL8MGIPYIDFigVbd+cTIeXfuxS+5+yQWiCPn3X4o
|
||||
X3Y2EaRfMOOojkbN2XKprCMGOM2TyDoakrfm3tcZ59/+nw7EnQef/dGqPJnKELhTLHzGtcNzT77+X7Hh
|
||||
wQXdsuOeDAz1TKgGWazktG87M6dx95P/vcde/u8/8ep/4Zo772Sz9tsw+K8X8Oo9N7Nr18PP666+/1+z
|
||||
8d5VsDgykEvZ4ZO/6taHroPP/sfOvHSvZM3tL7EzLt5hcFsuC1ZnPJNLJWtvYenqGx/mnnr1P3jCme0M
|
||||
9vMFoGaksTrVHZxZv/3h/9T5l96IRW/wMyvZU2ZVtnsKg0UvJ8Kiejbjwp2tHTvv/61Ye/OjfPJGD4ic
|
||||
UreYf8ehU9Wb7v33btq/jUG9kxdoIyuDy0x+9AAT8J6rnzD99KvaDXf+qyStLofIq9TLWJbtuBUw5cJ/
|
||||
3fQ10xkYQplxhrRVv7pV1e7ngVPO/5eNWNQIdUGxmHrKmhN61Uf+q8QtWc7AEI8a9xa9Qjy2XcFAi/jE
|
||||
PCdH6RTt/q5Tuve3iNfUZJhFzPKBMybole7/r5G8+j6nfpUZsguEHLvcjNJXPlPwnzZdKXL+CfWSg/81
|
||||
U1c/5bZo0oWrEzCtttNKWvFKK3/3fznfyQe5VHINYV6RcO6q1crd+V8hdfMfhfTt/9Syd/yX8+oHetWY
|
||||
FckiY1YJh+Y6zeS137SydvzXjZ53R8y0KpCBwZVbJWDqVrHEHf/ZInf8F07Y8V/Rf9otVtUsjBTJyMBv
|
||||
LyBmXtqpHTHvk27IlGt8KuFuDCK2RhrB0x4rJW3+LxmzARjym/7rBE99wqkQY47sTUYghx2IxRgY+I04
|
||||
xW3yWHnUUoB8LwYm7ghuOc+pvCoRy3lUIxfzqcUsEFSPamIV1NOB6gHpBQNQ2gaFPi8QCwKxKBBLArEU
|
||||
EEtA+cJAWgCIuaGawfkBAATBFuWVyulDAAAAAElFTkSuQmCC
|
||||
</value>
|
||||
</data>
|
||||
</root>
|
@ -1,131 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
partial class FlightControlPidsView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
this.txtSend = new System.Windows.Forms.TextBox();
|
||||
this.button1 = new System.Windows.Forms.Button();
|
||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||
this.stableConfigView1 = new ArducopterConfigurator.Views.StableConfigView();
|
||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||
this.acroConfigView1 = new ArducopterConfigurator.Views.AcroConfigView();
|
||||
this.FlightControlPidsBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.groupBox1.SuspendLayout();
|
||||
this.groupBox2.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.FlightControlPidsBindingSource)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// txtSend
|
||||
//
|
||||
this.txtSend.Location = new System.Drawing.Point(-167, 167);
|
||||
this.txtSend.Name = "txtSend";
|
||||
this.txtSend.Size = new System.Drawing.Size(10, 20);
|
||||
this.txtSend.TabIndex = 4;
|
||||
//
|
||||
// button1
|
||||
//
|
||||
this.button1.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.button1.Location = new System.Drawing.Point(980, 929);
|
||||
this.button1.Name = "button1";
|
||||
this.button1.Size = new System.Drawing.Size(104, 23);
|
||||
this.button1.TabIndex = 6;
|
||||
this.button1.Text = "Send Command";
|
||||
this.button1.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// groupBox1
|
||||
//
|
||||
this.groupBox1.Controls.Add(this.stableConfigView1);
|
||||
this.groupBox1.Location = new System.Drawing.Point(7, 9);
|
||||
this.groupBox1.Name = "groupBox1";
|
||||
this.groupBox1.Size = new System.Drawing.Size(283, 176);
|
||||
this.groupBox1.TabIndex = 9;
|
||||
this.groupBox1.TabStop = false;
|
||||
this.groupBox1.Text = "Stable Mode";
|
||||
//
|
||||
// stableConfigView1
|
||||
//
|
||||
this.stableConfigView1.Location = new System.Drawing.Point(7, 20);
|
||||
this.stableConfigView1.Name = "stableConfigView1";
|
||||
this.stableConfigView1.Size = new System.Drawing.Size(271, 150);
|
||||
this.stableConfigView1.TabIndex = 0;
|
||||
//
|
||||
// groupBox2
|
||||
//
|
||||
this.groupBox2.Controls.Add(this.acroConfigView1);
|
||||
this.groupBox2.Location = new System.Drawing.Point(7, 191);
|
||||
this.groupBox2.Name = "groupBox2";
|
||||
this.groupBox2.Size = new System.Drawing.Size(283, 164);
|
||||
this.groupBox2.TabIndex = 10;
|
||||
this.groupBox2.TabStop = false;
|
||||
this.groupBox2.Text = "Acro Mode";
|
||||
//
|
||||
// acroConfigView1
|
||||
//
|
||||
this.acroConfigView1.Location = new System.Drawing.Point(7, 20);
|
||||
this.acroConfigView1.Name = "acroConfigView1";
|
||||
this.acroConfigView1.Size = new System.Drawing.Size(271, 136);
|
||||
this.acroConfigView1.TabIndex = 0;
|
||||
//
|
||||
// FlightControlPidsBindingSource
|
||||
//
|
||||
this.FlightControlPidsBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.FlightControlPidsVm);
|
||||
//
|
||||
// FlightControlPidsView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.AutoSize = true;
|
||||
this.AutoSizeMode = System.Windows.Forms.AutoSizeMode.GrowAndShrink;
|
||||
this.Controls.Add(this.groupBox2);
|
||||
this.Controls.Add(this.groupBox1);
|
||||
this.Controls.Add(this.button1);
|
||||
this.Controls.Add(this.txtSend);
|
||||
this.Name = "FlightControlPidsView";
|
||||
this.Size = new System.Drawing.Size(542, 476);
|
||||
this.groupBox1.ResumeLayout(false);
|
||||
this.groupBox2.ResumeLayout(false);
|
||||
((System.ComponentModel.ISupportInitialize)(this.FlightControlPidsBindingSource)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.TextBox txtSend;
|
||||
private System.Windows.Forms.BindingSource FlightControlPidsBindingSource;
|
||||
private System.Windows.Forms.Button button1;
|
||||
private System.Windows.Forms.GroupBox groupBox1;
|
||||
private System.Windows.Forms.GroupBox groupBox2;
|
||||
private ArducopterConfigurator.Views.StableConfigView stableConfigView1;
|
||||
private ArducopterConfigurator.Views.AcroConfigView acroConfigView1;
|
||||
}
|
||||
}
|
@ -1,38 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public partial class FlightControlPidsView : UserControl, IView<FlightControlPidsVm>
|
||||
{
|
||||
private IPresentationModel _vm;
|
||||
|
||||
public FlightControlPidsView()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public void SetDataContext(FlightControlPidsVm vm)
|
||||
{
|
||||
FlightControlPidsBindingSource.DataSource = vm;
|
||||
_vm = vm;
|
||||
|
||||
stableConfigView1.SetDataContext(vm.Vm2);
|
||||
acroConfigView1.SetDataContext(vm.Vm1);
|
||||
}
|
||||
|
||||
|
||||
public Control Control
|
||||
{
|
||||
get { return this; }
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -1,123 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="FlightControlPidsBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
@ -1,752 +0,0 @@
|
||||
namespace ArducopterConfigurator.views
|
||||
{
|
||||
partial class FlightDataView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightDataView));
|
||||
this.textBox1 = new System.Windows.Forms.TextBox();
|
||||
this.FlightDataVmBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.textBox2 = new System.Windows.Forms.TextBox();
|
||||
this.textBox3 = new System.Windows.Forms.TextBox();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.textBox4 = new System.Windows.Forms.TextBox();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
this.label8 = new System.Windows.Forms.Label();
|
||||
this.textBox5 = new System.Windows.Forms.TextBox();
|
||||
this.label9 = new System.Windows.Forms.Label();
|
||||
this.textBox6 = new System.Windows.Forms.TextBox();
|
||||
this.label10 = new System.Windows.Forms.Label();
|
||||
this.textBox7 = new System.Windows.Forms.TextBox();
|
||||
this.textBox8 = new System.Windows.Forms.TextBox();
|
||||
this.textBox9 = new System.Windows.Forms.TextBox();
|
||||
this.textBox10 = new System.Windows.Forms.TextBox();
|
||||
this.indicatorRollGyro = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.indicatorRollAccel = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.linearIndicatorControl1 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.linearIndicatorControl2 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.linearIndicatorControl7 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.linearIndicatorControl8 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.textBox11 = new System.Windows.Forms.TextBox();
|
||||
this.textBox12 = new System.Windows.Forms.TextBox();
|
||||
this.textBox13 = new System.Windows.Forms.TextBox();
|
||||
this.button2 = new System.Windows.Forms.Button();
|
||||
this.button1 = new System.Windows.Forms.Button();
|
||||
this.button3 = new System.Windows.Forms.Button();
|
||||
this.label11 = new System.Windows.Forms.Label();
|
||||
this.label12 = new System.Windows.Forms.Label();
|
||||
this.label13 = new System.Windows.Forms.Label();
|
||||
this.pictureBox1 = new System.Windows.Forms.PictureBox();
|
||||
this.pictureBox2 = new System.Windows.Forms.PictureBox();
|
||||
this.cirularIndicatorControl1 = new ArducopterConfigurator.Views.controls.CirularIndicatorControl();
|
||||
this.cirularIndicatorControl2 = new ArducopterConfigurator.Views.controls.CirularIndicatorControl();
|
||||
this.cirularIndicatorControl3 = new ArducopterConfigurator.Views.controls.CirularIndicatorControl();
|
||||
this.cirularIndicatorControl4 = new ArducopterConfigurator.Views.controls.CirularIndicatorControl();
|
||||
this.cirularIndicatorControl5 = new ArducopterConfigurator.Views.controls.CirularIndicatorControl();
|
||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.textBox14 = new System.Windows.Forms.TextBox();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.compassControl1 = new ArducopterConfigurator.Views.controls.CompassControl();
|
||||
((System.ComponentModel.ISupportInitialize)(this.FlightDataVmBindingSource)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// textBox1
|
||||
//
|
||||
this.textBox1.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "MotorLeft", true));
|
||||
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.FlightDataVmBindingSource, "IsArmed", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox1.Enabled = false;
|
||||
this.textBox1.Location = new System.Drawing.Point(99, 162);
|
||||
this.textBox1.Name = "textBox1";
|
||||
this.textBox1.ReadOnly = true;
|
||||
this.textBox1.Size = new System.Drawing.Size(38, 13);
|
||||
this.textBox1.TabIndex = 8;
|
||||
//
|
||||
// FlightDataVmBindingSource
|
||||
//
|
||||
this.FlightDataVmBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.SensorsVm);
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(82, 48);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(15, 13);
|
||||
this.label5.TabIndex = 10;
|
||||
this.label5.Text = "G";
|
||||
//
|
||||
// textBox2
|
||||
//
|
||||
this.textBox2.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox2.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "GyroRoll", true));
|
||||
this.textBox2.Enabled = false;
|
||||
this.textBox2.Location = new System.Drawing.Point(217, 48);
|
||||
this.textBox2.Name = "textBox2";
|
||||
this.textBox2.ReadOnly = true;
|
||||
this.textBox2.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox2.TabIndex = 12;
|
||||
//
|
||||
// textBox3
|
||||
//
|
||||
this.textBox3.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox3.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "AccelRoll", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox3.Enabled = false;
|
||||
this.textBox3.Location = new System.Drawing.Point(217, 29);
|
||||
this.textBox3.Name = "textBox3";
|
||||
this.textBox3.ReadOnly = true;
|
||||
this.textBox3.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox3.TabIndex = 13;
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(82, 28);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(14, 13);
|
||||
this.label6.TabIndex = 15;
|
||||
this.label6.Text = "A";
|
||||
//
|
||||
// textBox4
|
||||
//
|
||||
this.textBox4.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "GyroPitch", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox4.Enabled = false;
|
||||
this.textBox4.Location = new System.Drawing.Point(65, 171);
|
||||
this.textBox4.Name = "textBox4";
|
||||
this.textBox4.ReadOnly = true;
|
||||
this.textBox4.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox4.TabIndex = 17;
|
||||
this.textBox4.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(48, 67);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(14, 13);
|
||||
this.label7.TabIndex = 18;
|
||||
this.label7.Text = "A";
|
||||
//
|
||||
// label8
|
||||
//
|
||||
this.label8.AutoSize = true;
|
||||
this.label8.Location = new System.Drawing.Point(68, 67);
|
||||
this.label8.Name = "label8";
|
||||
this.label8.Size = new System.Drawing.Size(15, 13);
|
||||
this.label8.TabIndex = 21;
|
||||
this.label8.Text = "G";
|
||||
//
|
||||
// textBox5
|
||||
//
|
||||
this.textBox5.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox5.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "AccelPitch", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox5.Enabled = false;
|
||||
this.textBox5.Location = new System.Drawing.Point(27, 171);
|
||||
this.textBox5.Name = "textBox5";
|
||||
this.textBox5.ReadOnly = true;
|
||||
this.textBox5.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox5.TabIndex = 20;
|
||||
this.textBox5.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label9
|
||||
//
|
||||
this.label9.AutoSize = true;
|
||||
this.label9.Location = new System.Drawing.Point(43, 221);
|
||||
this.label9.Name = "label9";
|
||||
this.label9.Size = new System.Drawing.Size(53, 13);
|
||||
this.label9.TabIndex = 27;
|
||||
this.label9.Text = "Yaw Gyro";
|
||||
//
|
||||
// textBox6
|
||||
//
|
||||
this.textBox6.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox6.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "GyroYaw", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox6.Enabled = false;
|
||||
this.textBox6.Location = new System.Drawing.Point(216, 222);
|
||||
this.textBox6.Name = "textBox6";
|
||||
this.textBox6.ReadOnly = true;
|
||||
this.textBox6.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox6.TabIndex = 26;
|
||||
//
|
||||
// label10
|
||||
//
|
||||
this.label10.AutoSize = true;
|
||||
this.label10.Location = new System.Drawing.Point(221, 67);
|
||||
this.label10.Name = "label10";
|
||||
this.label10.Size = new System.Drawing.Size(44, 13);
|
||||
this.label10.TabIndex = 24;
|
||||
this.label10.Text = "Accel Z";
|
||||
//
|
||||
// textBox7
|
||||
//
|
||||
this.textBox7.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox7.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "AccelZ", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox7.Enabled = false;
|
||||
this.textBox7.Location = new System.Drawing.Point(230, 171);
|
||||
this.textBox7.Name = "textBox7";
|
||||
this.textBox7.ReadOnly = true;
|
||||
this.textBox7.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox7.TabIndex = 23;
|
||||
this.textBox7.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// textBox8
|
||||
//
|
||||
this.textBox8.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox8.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "MotorFront", true));
|
||||
this.textBox8.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.FlightDataVmBindingSource, "IsArmed", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox8.Enabled = false;
|
||||
this.textBox8.Location = new System.Drawing.Point(182, 83);
|
||||
this.textBox8.Name = "textBox8";
|
||||
this.textBox8.ReadOnly = true;
|
||||
this.textBox8.Size = new System.Drawing.Size(38, 13);
|
||||
this.textBox8.TabIndex = 29;
|
||||
//
|
||||
// textBox9
|
||||
//
|
||||
this.textBox9.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox9.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "MotorRear", true));
|
||||
this.textBox9.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.FlightDataVmBindingSource, "IsArmed", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox9.Enabled = false;
|
||||
this.textBox9.Location = new System.Drawing.Point(107, 192);
|
||||
this.textBox9.Name = "textBox9";
|
||||
this.textBox9.ReadOnly = true;
|
||||
this.textBox9.Size = new System.Drawing.Size(32, 13);
|
||||
this.textBox9.TabIndex = 30;
|
||||
//
|
||||
// textBox10
|
||||
//
|
||||
this.textBox10.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox10.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "MotorRight", true));
|
||||
this.textBox10.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.FlightDataVmBindingSource, "IsArmed", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox10.Enabled = false;
|
||||
this.textBox10.Location = new System.Drawing.Point(186, 163);
|
||||
this.textBox10.Name = "textBox10";
|
||||
this.textBox10.ReadOnly = true;
|
||||
this.textBox10.Size = new System.Drawing.Size(38, 13);
|
||||
this.textBox10.TabIndex = 31;
|
||||
//
|
||||
// indicatorRollGyro
|
||||
//
|
||||
this.indicatorRollGyro.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.indicatorRollGyro.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.indicatorRollGyro.BarBorderColor = System.Drawing.Color.Maroon;
|
||||
this.indicatorRollGyro.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.indicatorRollGyro.BarDividersCount = 20;
|
||||
this.indicatorRollGyro.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.indicatorRollGyro.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "GyroRoll", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.indicatorRollGyro.IsVertical = false;
|
||||
this.indicatorRollGyro.Location = new System.Drawing.Point(102, 48);
|
||||
this.indicatorRollGyro.Max = 500;
|
||||
this.indicatorRollGyro.MaxWaterMark = 0;
|
||||
this.indicatorRollGyro.Min = -500;
|
||||
this.indicatorRollGyro.MinWatermark = 0;
|
||||
this.indicatorRollGyro.Name = "indicatorRollGyro";
|
||||
this.indicatorRollGyro.Offset = 0;
|
||||
this.indicatorRollGyro.Size = new System.Drawing.Size(109, 14);
|
||||
this.indicatorRollGyro.TabIndex = 32;
|
||||
this.toolTip1.SetToolTip(this.indicatorRollGyro, "Roll Gyro");
|
||||
this.indicatorRollGyro.Value = 100;
|
||||
this.indicatorRollGyro.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
//
|
||||
// indicatorRollAccel
|
||||
//
|
||||
this.indicatorRollAccel.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.indicatorRollAccel.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.indicatorRollAccel.BarBorderColor = System.Drawing.Color.Maroon;
|
||||
this.indicatorRollAccel.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.indicatorRollAccel.BarDividersCount = 20;
|
||||
this.indicatorRollAccel.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.indicatorRollAccel.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "AccelRoll", true));
|
||||
this.indicatorRollAccel.IsVertical = false;
|
||||
this.indicatorRollAccel.Location = new System.Drawing.Point(102, 28);
|
||||
this.indicatorRollAccel.Max = 500;
|
||||
this.indicatorRollAccel.MaxWaterMark = 0;
|
||||
this.indicatorRollAccel.Min = -500;
|
||||
this.indicatorRollAccel.MinWatermark = 0;
|
||||
this.indicatorRollAccel.Name = "indicatorRollAccel";
|
||||
this.indicatorRollAccel.Offset = 0;
|
||||
this.indicatorRollAccel.Size = new System.Drawing.Size(109, 14);
|
||||
this.indicatorRollAccel.TabIndex = 33;
|
||||
this.toolTip1.SetToolTip(this.indicatorRollAccel, "Roll Accelerometer");
|
||||
this.indicatorRollAccel.Value = 100;
|
||||
this.indicatorRollAccel.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
//
|
||||
// linearIndicatorControl1
|
||||
//
|
||||
this.linearIndicatorControl1.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.linearIndicatorControl1.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.linearIndicatorControl1.BarBorderColor = System.Drawing.Color.Maroon;
|
||||
this.linearIndicatorControl1.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl1.BarDividersCount = 20;
|
||||
this.linearIndicatorControl1.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl1.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "GyroPitch", true));
|
||||
this.linearIndicatorControl1.IsVertical = true;
|
||||
this.linearIndicatorControl1.Location = new System.Drawing.Point(66, 83);
|
||||
this.linearIndicatorControl1.Max = 500;
|
||||
this.linearIndicatorControl1.MaxWaterMark = 0;
|
||||
this.linearIndicatorControl1.Min = -500;
|
||||
this.linearIndicatorControl1.MinWatermark = 0;
|
||||
this.linearIndicatorControl1.Name = "linearIndicatorControl1";
|
||||
this.linearIndicatorControl1.Offset = 0;
|
||||
this.linearIndicatorControl1.Size = new System.Drawing.Size(14, 82);
|
||||
this.linearIndicatorControl1.TabIndex = 34;
|
||||
this.toolTip1.SetToolTip(this.linearIndicatorControl1, "Pitch Gyro");
|
||||
this.linearIndicatorControl1.Value = 100;
|
||||
this.linearIndicatorControl1.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
//
|
||||
// linearIndicatorControl2
|
||||
//
|
||||
this.linearIndicatorControl2.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.linearIndicatorControl2.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.linearIndicatorControl2.BarBorderColor = System.Drawing.Color.Maroon;
|
||||
this.linearIndicatorControl2.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl2.BarDividersCount = 20;
|
||||
this.linearIndicatorControl2.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl2.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "AccelPitch", true));
|
||||
this.linearIndicatorControl2.IsVertical = true;
|
||||
this.linearIndicatorControl2.Location = new System.Drawing.Point(48, 83);
|
||||
this.linearIndicatorControl2.Max = 500;
|
||||
this.linearIndicatorControl2.MaxWaterMark = 0;
|
||||
this.linearIndicatorControl2.Min = -500;
|
||||
this.linearIndicatorControl2.MinWatermark = 0;
|
||||
this.linearIndicatorControl2.Name = "linearIndicatorControl2";
|
||||
this.linearIndicatorControl2.Offset = 0;
|
||||
this.linearIndicatorControl2.Size = new System.Drawing.Size(14, 82);
|
||||
this.linearIndicatorControl2.TabIndex = 35;
|
||||
this.toolTip1.SetToolTip(this.linearIndicatorControl2, "Pitch Accelerometer");
|
||||
this.linearIndicatorControl2.Value = 100;
|
||||
this.linearIndicatorControl2.WatermarkLineColor = System.Drawing.Color.Red;
|
||||
//
|
||||
// linearIndicatorControl7
|
||||
//
|
||||
this.linearIndicatorControl7.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.linearIndicatorControl7.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.linearIndicatorControl7.BarBorderColor = System.Drawing.Color.Maroon;
|
||||
this.linearIndicatorControl7.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl7.BarDividersCount = 20;
|
||||
this.linearIndicatorControl7.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "GyroYaw", true));
|
||||
this.linearIndicatorControl7.IsVertical = false;
|
||||
this.linearIndicatorControl7.Location = new System.Drawing.Point(102, 221);
|
||||
this.linearIndicatorControl7.Max = 500;
|
||||
this.linearIndicatorControl7.MaxWaterMark = 0;
|
||||
this.linearIndicatorControl7.Min = -500;
|
||||
this.linearIndicatorControl7.MinWatermark = 0;
|
||||
this.linearIndicatorControl7.Name = "linearIndicatorControl7";
|
||||
this.linearIndicatorControl7.Offset = 0;
|
||||
this.linearIndicatorControl7.Size = new System.Drawing.Size(109, 14);
|
||||
this.linearIndicatorControl7.TabIndex = 40;
|
||||
this.toolTip1.SetToolTip(this.linearIndicatorControl7, "Yaw Gyro");
|
||||
this.linearIndicatorControl7.Value = 100;
|
||||
this.linearIndicatorControl7.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
//
|
||||
// linearIndicatorControl8
|
||||
//
|
||||
this.linearIndicatorControl8.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.linearIndicatorControl8.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.linearIndicatorControl8.BarBorderColor = System.Drawing.Color.Maroon;
|
||||
this.linearIndicatorControl8.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl8.BarDividersCount = 20;
|
||||
this.linearIndicatorControl8.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "AccelZ", true));
|
||||
this.linearIndicatorControl8.IsVertical = true;
|
||||
this.linearIndicatorControl8.Location = new System.Drawing.Point(241, 83);
|
||||
this.linearIndicatorControl8.Max = 500;
|
||||
this.linearIndicatorControl8.MaxWaterMark = 0;
|
||||
this.linearIndicatorControl8.Min = -500;
|
||||
this.linearIndicatorControl8.MinWatermark = 0;
|
||||
this.linearIndicatorControl8.Name = "linearIndicatorControl8";
|
||||
this.linearIndicatorControl8.Offset = 0;
|
||||
this.linearIndicatorControl8.Size = new System.Drawing.Size(14, 82);
|
||||
this.linearIndicatorControl8.TabIndex = 41;
|
||||
this.toolTip1.SetToolTip(this.linearIndicatorControl8, "Z Accelerometer");
|
||||
this.linearIndicatorControl8.Value = 100;
|
||||
this.linearIndicatorControl8.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
//
|
||||
// textBox11
|
||||
//
|
||||
this.textBox11.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
|
||||
this.textBox11.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "AccelRollOffset", true));
|
||||
this.textBox11.Location = new System.Drawing.Point(139, 7);
|
||||
this.textBox11.Name = "textBox11";
|
||||
this.textBox11.ReadOnly = true;
|
||||
this.textBox11.Size = new System.Drawing.Size(35, 20);
|
||||
this.textBox11.TabIndex = 42;
|
||||
this.textBox11.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
this.toolTip1.SetToolTip(this.textBox11, "Roll Accelerometer Calibration Offset");
|
||||
//
|
||||
// textBox12
|
||||
//
|
||||
this.textBox12.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
|
||||
this.textBox12.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "AccelZOffset", true));
|
||||
this.textBox12.Location = new System.Drawing.Point(260, 108);
|
||||
this.textBox12.Name = "textBox12";
|
||||
this.textBox12.ReadOnly = true;
|
||||
this.textBox12.Size = new System.Drawing.Size(34, 20);
|
||||
this.textBox12.TabIndex = 43;
|
||||
this.textBox12.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
this.toolTip1.SetToolTip(this.textBox12, "Z Accelerometer Calibration Offset");
|
||||
//
|
||||
// textBox13
|
||||
//
|
||||
this.textBox13.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
|
||||
this.textBox13.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "AccelPitchOffset", true));
|
||||
this.textBox13.Location = new System.Drawing.Point(8, 108);
|
||||
this.textBox13.Name = "textBox13";
|
||||
this.textBox13.ReadOnly = true;
|
||||
this.textBox13.Size = new System.Drawing.Size(34, 20);
|
||||
this.textBox13.TabIndex = 44;
|
||||
this.textBox13.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
this.toolTip1.SetToolTip(this.textBox13, "Pictch Accelerometer Calibration Offset");
|
||||
//
|
||||
// button2
|
||||
//
|
||||
this.button2.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.FlightDataVmBindingSource, "RefreshCalibrationOffsetsCommand", true));
|
||||
this.button2.Image = ((System.Drawing.Image)(resources.GetObject("button2.Image")));
|
||||
this.button2.Location = new System.Drawing.Point(304, 139);
|
||||
this.button2.Name = "button2";
|
||||
this.button2.Size = new System.Drawing.Size(26, 26);
|
||||
this.button2.TabIndex = 46;
|
||||
this.button2.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// button1
|
||||
//
|
||||
this.button1.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.FlightDataVmBindingSource, "UpdateCalibrationOffsetsCommand", true));
|
||||
this.button1.Image = ((System.Drawing.Image)(resources.GetObject("button1.Image")));
|
||||
this.button1.Location = new System.Drawing.Point(304, 110);
|
||||
this.button1.Name = "button1";
|
||||
this.button1.Size = new System.Drawing.Size(26, 26);
|
||||
this.button1.TabIndex = 45;
|
||||
this.button1.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// button3
|
||||
//
|
||||
this.button3.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.FlightDataVmBindingSource, "CalculateCalibrationOffsetsCommand", true));
|
||||
this.button3.Image = ((System.Drawing.Image)(resources.GetObject("button3.Image")));
|
||||
this.button3.Location = new System.Drawing.Point(304, 81);
|
||||
this.button3.Name = "button3";
|
||||
this.button3.Size = new System.Drawing.Size(26, 26);
|
||||
this.button3.TabIndex = 47;
|
||||
this.toolTip1.SetToolTip(this.button3, "Calibrate Accelerometers");
|
||||
this.button3.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// label11
|
||||
//
|
||||
this.label11.AutoSize = true;
|
||||
this.label11.Location = new System.Drawing.Point(336, 88);
|
||||
this.label11.Name = "label11";
|
||||
this.label11.Size = new System.Drawing.Size(78, 13);
|
||||
this.label11.TabIndex = 48;
|
||||
this.label11.Text = "Begin Calibrate";
|
||||
//
|
||||
// label12
|
||||
//
|
||||
this.label12.AutoSize = true;
|
||||
this.label12.Location = new System.Drawing.Point(336, 117);
|
||||
this.label12.Name = "label12";
|
||||
this.label12.Size = new System.Drawing.Size(84, 13);
|
||||
this.label12.TabIndex = 49;
|
||||
this.label12.Text = "Save Calibration";
|
||||
//
|
||||
// label13
|
||||
//
|
||||
this.label13.AutoSize = true;
|
||||
this.label13.Location = new System.Drawing.Point(336, 148);
|
||||
this.label13.Name = "label13";
|
||||
this.label13.Size = new System.Drawing.Size(96, 13);
|
||||
this.label13.TabIndex = 50;
|
||||
this.label13.Text = "Refresh Calibration";
|
||||
//
|
||||
// pictureBox1
|
||||
//
|
||||
this.pictureBox1.BackColor = System.Drawing.Color.DimGray;
|
||||
this.pictureBox1.Location = new System.Drawing.Point(117, 138);
|
||||
this.pictureBox1.Name = "pictureBox1";
|
||||
this.pictureBox1.Size = new System.Drawing.Size(89, 6);
|
||||
this.pictureBox1.TabIndex = 51;
|
||||
this.pictureBox1.TabStop = false;
|
||||
//
|
||||
// pictureBox2
|
||||
//
|
||||
this.pictureBox2.BackColor = System.Drawing.Color.DimGray;
|
||||
this.pictureBox2.Location = new System.Drawing.Point(155, 102);
|
||||
this.pictureBox2.Name = "pictureBox2";
|
||||
this.pictureBox2.Size = new System.Drawing.Size(6, 67);
|
||||
this.pictureBox2.TabIndex = 52;
|
||||
this.pictureBox2.TabStop = false;
|
||||
//
|
||||
// cirularIndicatorControl1
|
||||
//
|
||||
this.cirularIndicatorControl1.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.cirularIndicatorControl1.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.cirularIndicatorControl1.BarBorderColor = System.Drawing.Color.DarkGray;
|
||||
this.cirularIndicatorControl1.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.cirularIndicatorControl1.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.cirularIndicatorControl1.IsReveresed = false;
|
||||
this.cirularIndicatorControl1.IsVertical = false;
|
||||
this.cirularIndicatorControl1.Location = new System.Drawing.Point(120, 115);
|
||||
this.cirularIndicatorControl1.Max = 100;
|
||||
this.cirularIndicatorControl1.Min = 0;
|
||||
this.cirularIndicatorControl1.Name = "cirularIndicatorControl1";
|
||||
this.cirularIndicatorControl1.Offset = 0;
|
||||
this.cirularIndicatorControl1.Size = new System.Drawing.Size(40, 40);
|
||||
this.cirularIndicatorControl1.TabIndex = 53;
|
||||
this.cirularIndicatorControl1.Value = 50;
|
||||
//
|
||||
// cirularIndicatorControl2
|
||||
//
|
||||
this.cirularIndicatorControl2.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.cirularIndicatorControl2.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.cirularIndicatorControl2.BarBorderColor = System.Drawing.Color.DimGray;
|
||||
this.cirularIndicatorControl2.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.cirularIndicatorControl2.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(128)))), ((int)(((byte)(128)))));
|
||||
this.cirularIndicatorControl2.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "MotorLeft", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.cirularIndicatorControl2.IsReveresed = false;
|
||||
this.cirularIndicatorControl2.IsVertical = true;
|
||||
this.cirularIndicatorControl2.Location = new System.Drawing.Point(99, 121);
|
||||
this.cirularIndicatorControl2.Max = 2000;
|
||||
this.cirularIndicatorControl2.Min = 1000;
|
||||
this.cirularIndicatorControl2.Name = "cirularIndicatorControl2";
|
||||
this.cirularIndicatorControl2.Offset = 0;
|
||||
this.cirularIndicatorControl2.Size = new System.Drawing.Size(40, 40);
|
||||
this.cirularIndicatorControl2.TabIndex = 53;
|
||||
this.cirularIndicatorControl2.Value = 1500;
|
||||
//
|
||||
// cirularIndicatorControl3
|
||||
//
|
||||
this.cirularIndicatorControl3.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.cirularIndicatorControl3.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.cirularIndicatorControl3.BarBorderColor = System.Drawing.Color.DimGray;
|
||||
this.cirularIndicatorControl3.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.cirularIndicatorControl3.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(128)))), ((int)(((byte)(128)))));
|
||||
this.cirularIndicatorControl3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "MotorRight", true));
|
||||
this.cirularIndicatorControl3.IsReveresed = false;
|
||||
this.cirularIndicatorControl3.IsVertical = true;
|
||||
this.cirularIndicatorControl3.Location = new System.Drawing.Point(182, 121);
|
||||
this.cirularIndicatorControl3.Max = 2000;
|
||||
this.cirularIndicatorControl3.Min = 1000;
|
||||
this.cirularIndicatorControl3.Name = "cirularIndicatorControl3";
|
||||
this.cirularIndicatorControl3.Offset = 0;
|
||||
this.cirularIndicatorControl3.Size = new System.Drawing.Size(40, 40);
|
||||
this.cirularIndicatorControl3.TabIndex = 54;
|
||||
this.cirularIndicatorControl3.Value = 1500;
|
||||
//
|
||||
// cirularIndicatorControl4
|
||||
//
|
||||
this.cirularIndicatorControl4.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.cirularIndicatorControl4.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.cirularIndicatorControl4.BarBorderColor = System.Drawing.Color.DimGray;
|
||||
this.cirularIndicatorControl4.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.cirularIndicatorControl4.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(128)))), ((int)(((byte)(128)))));
|
||||
this.cirularIndicatorControl4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "MotorRear", true));
|
||||
this.cirularIndicatorControl4.IsReveresed = false;
|
||||
this.cirularIndicatorControl4.IsVertical = true;
|
||||
this.cirularIndicatorControl4.Location = new System.Drawing.Point(138, 157);
|
||||
this.cirularIndicatorControl4.Max = 2000;
|
||||
this.cirularIndicatorControl4.Min = 1000;
|
||||
this.cirularIndicatorControl4.Name = "cirularIndicatorControl4";
|
||||
this.cirularIndicatorControl4.Offset = 0;
|
||||
this.cirularIndicatorControl4.Size = new System.Drawing.Size(40, 40);
|
||||
this.cirularIndicatorControl4.TabIndex = 55;
|
||||
this.cirularIndicatorControl4.Value = 1500;
|
||||
//
|
||||
// cirularIndicatorControl5
|
||||
//
|
||||
this.cirularIndicatorControl5.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.cirularIndicatorControl5.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.cirularIndicatorControl5.BarBorderColor = System.Drawing.Color.DimGray;
|
||||
this.cirularIndicatorControl5.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.cirularIndicatorControl5.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(128)))), ((int)(((byte)(128)))));
|
||||
this.cirularIndicatorControl5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "MotorFront", true));
|
||||
this.cirularIndicatorControl5.IsReveresed = false;
|
||||
this.cirularIndicatorControl5.IsVertical = true;
|
||||
this.cirularIndicatorControl5.Location = new System.Drawing.Point(138, 83);
|
||||
this.cirularIndicatorControl5.Max = 2000;
|
||||
this.cirularIndicatorControl5.Min = 1000;
|
||||
this.cirularIndicatorControl5.Name = "cirularIndicatorControl5";
|
||||
this.cirularIndicatorControl5.Offset = 0;
|
||||
this.cirularIndicatorControl5.Size = new System.Drawing.Size(40, 40);
|
||||
this.cirularIndicatorControl5.TabIndex = 56;
|
||||
this.cirularIndicatorControl5.Value = 1500;
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
|
||||
this.label1.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.FlightDataVmBindingSource, "IsArmed", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.label1.Font = new System.Drawing.Font("Microsoft Sans Serif", 10F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
this.label1.ForeColor = System.Drawing.Color.Red;
|
||||
this.label1.Location = new System.Drawing.Point(308, 29);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(59, 19);
|
||||
this.label1.TabIndex = 57;
|
||||
this.label1.Text = "ARMED";
|
||||
//
|
||||
// textBox14
|
||||
//
|
||||
this.textBox14.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox14.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "CompassHeadingDegrees", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "N0"));
|
||||
this.textBox14.Enabled = false;
|
||||
this.textBox14.Location = new System.Drawing.Point(264, 222);
|
||||
this.textBox14.Name = "textBox14";
|
||||
this.textBox14.ReadOnly = true;
|
||||
this.textBox14.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox14.TabIndex = 58;
|
||||
this.textBox14.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(255, 205);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(47, 13);
|
||||
this.label2.TabIndex = 59;
|
||||
this.label2.Text = "Heading";
|
||||
//
|
||||
// compassControl1
|
||||
//
|
||||
this.compassControl1.BarBackgroundDark = System.Drawing.Color.FromArgb(((int)(((byte)(199)))), ((int)(((byte)(200)))), ((int)(((byte)(201)))));
|
||||
this.compassControl1.BarBackgroundLight = System.Drawing.Color.WhiteSmoke;
|
||||
this.compassControl1.BarBorderColor = System.Drawing.Color.Black;
|
||||
this.compassControl1.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.compassControl1.BarLight = System.Drawing.Color.LightBlue;
|
||||
this.compassControl1.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.FlightDataVmBindingSource, "CompassHeadingDegrees", true));
|
||||
this.compassControl1.Location = new System.Drawing.Point(308, 192);
|
||||
this.compassControl1.Name = "compassControl1";
|
||||
this.compassControl1.Size = new System.Drawing.Size(50, 50);
|
||||
this.compassControl1.TabIndex = 0;
|
||||
this.compassControl1.Value = 90;
|
||||
//
|
||||
// FlightDataView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.compassControl1);
|
||||
this.Controls.Add(this.label2);
|
||||
this.Controls.Add(this.textBox14);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.cirularIndicatorControl5);
|
||||
this.Controls.Add(this.cirularIndicatorControl4);
|
||||
this.Controls.Add(this.cirularIndicatorControl3);
|
||||
this.Controls.Add(this.cirularIndicatorControl2);
|
||||
this.Controls.Add(this.label13);
|
||||
this.Controls.Add(this.label12);
|
||||
this.Controls.Add(this.label11);
|
||||
this.Controls.Add(this.button3);
|
||||
this.Controls.Add(this.button2);
|
||||
this.Controls.Add(this.button1);
|
||||
this.Controls.Add(this.textBox13);
|
||||
this.Controls.Add(this.textBox12);
|
||||
this.Controls.Add(this.textBox11);
|
||||
this.Controls.Add(this.linearIndicatorControl8);
|
||||
this.Controls.Add(this.linearIndicatorControl7);
|
||||
this.Controls.Add(this.linearIndicatorControl2);
|
||||
this.Controls.Add(this.linearIndicatorControl1);
|
||||
this.Controls.Add(this.indicatorRollAccel);
|
||||
this.Controls.Add(this.indicatorRollGyro);
|
||||
this.Controls.Add(this.textBox10);
|
||||
this.Controls.Add(this.textBox9);
|
||||
this.Controls.Add(this.textBox8);
|
||||
this.Controls.Add(this.label9);
|
||||
this.Controls.Add(this.textBox6);
|
||||
this.Controls.Add(this.label10);
|
||||
this.Controls.Add(this.textBox7);
|
||||
this.Controls.Add(this.label8);
|
||||
this.Controls.Add(this.textBox5);
|
||||
this.Controls.Add(this.label7);
|
||||
this.Controls.Add(this.textBox4);
|
||||
this.Controls.Add(this.label6);
|
||||
this.Controls.Add(this.textBox3);
|
||||
this.Controls.Add(this.textBox2);
|
||||
this.Controls.Add(this.label5);
|
||||
this.Controls.Add(this.textBox1);
|
||||
this.Controls.Add(this.pictureBox1);
|
||||
this.Controls.Add(this.pictureBox2);
|
||||
this.DoubleBuffered = true;
|
||||
this.Name = "FlightDataView";
|
||||
this.Size = new System.Drawing.Size(453, 273);
|
||||
((System.ComponentModel.ISupportInitialize)(this.FlightDataVmBindingSource)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.BindingSource FlightDataVmBindingSource;
|
||||
private System.Windows.Forms.TextBox textBox1;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.TextBox textBox2;
|
||||
private System.Windows.Forms.TextBox textBox3;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.TextBox textBox4;
|
||||
private System.Windows.Forms.Label label7;
|
||||
private System.Windows.Forms.Label label8;
|
||||
private System.Windows.Forms.TextBox textBox5;
|
||||
private System.Windows.Forms.Label label9;
|
||||
private System.Windows.Forms.TextBox textBox6;
|
||||
private System.Windows.Forms.Label label10;
|
||||
private System.Windows.Forms.TextBox textBox7;
|
||||
private System.Windows.Forms.TextBox textBox8;
|
||||
private System.Windows.Forms.TextBox textBox9;
|
||||
private System.Windows.Forms.TextBox textBox10;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl indicatorRollGyro;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl indicatorRollAccel;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl1;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl2;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl7;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl8;
|
||||
private System.Windows.Forms.TextBox textBox11;
|
||||
private System.Windows.Forms.TextBox textBox12;
|
||||
private System.Windows.Forms.TextBox textBox13;
|
||||
private System.Windows.Forms.Button button2;
|
||||
private System.Windows.Forms.Button button1;
|
||||
private System.Windows.Forms.Button button3;
|
||||
private System.Windows.Forms.Label label11;
|
||||
private System.Windows.Forms.Label label12;
|
||||
private System.Windows.Forms.Label label13;
|
||||
private System.Windows.Forms.PictureBox pictureBox1;
|
||||
private System.Windows.Forms.PictureBox pictureBox2;
|
||||
private ArducopterConfigurator.Views.controls.CirularIndicatorControl cirularIndicatorControl1;
|
||||
private ArducopterConfigurator.Views.controls.CirularIndicatorControl cirularIndicatorControl2;
|
||||
private ArducopterConfigurator.Views.controls.CirularIndicatorControl cirularIndicatorControl3;
|
||||
private ArducopterConfigurator.Views.controls.CirularIndicatorControl cirularIndicatorControl4;
|
||||
private ArducopterConfigurator.Views.controls.CirularIndicatorControl cirularIndicatorControl5;
|
||||
private System.Windows.Forms.ToolTip toolTip1;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private System.Windows.Forms.TextBox textBox14;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private ArducopterConfigurator.Views.controls.CompassControl compassControl1;
|
||||
}
|
||||
}
|
@ -1,35 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using ArducopterConfigurator.Views;
|
||||
|
||||
namespace ArducopterConfigurator.views
|
||||
{
|
||||
public partial class FlightDataView : FlightDataViewDesignable
|
||||
{
|
||||
public FlightDataView()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
}
|
||||
|
||||
public override void SetDataContext(SensorsVm vm)
|
||||
{
|
||||
BindButtons(vm);
|
||||
|
||||
|
||||
FlightDataVmBindingSource.DataSource = vm;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
vm.PropertyChanged += ((sender, e) => FlightDataVmBindingSource.ResetBindings(false));
|
||||
}
|
||||
|
||||
}
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class FlightDataViewDesignable : ViewCommon<SensorsVm> { }
|
||||
}
|
@ -1,175 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="FlightDataVmBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>20, 28</value>
|
||||
</metadata>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>225, 28</value>
|
||||
</metadata>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="button2.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAYAAAAf8/9hAAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8
|
||||
YQUAAAAgY0hSTQAAeiYAAICEAAD6AAAAgOgAAHUwAADqYAAAOpgAABdwnLpRPAAAAAlwSFlzAAAOuAAA
|
||||
DrgBakH1WwAAAtVJREFUOE9jYKAaiN/PweB3RIohcL8MGIPYIDFigVbd+cTIeXfuxS+5+yQWiCPn3X4o
|
||||
X3Y2EaRfMOOojkbN2XKprCMGOM2TyDoakrfm3tcZ59/+nw7EnQef/dGqPJnKELhTLHzGtcNzT77+X7Hh
|
||||
wQXdsuOeDAz1TKgGWazktG87M6dx95P/vcde/u8/8ep/4Zo772Sz9tsw+K8X8Oo9N7Nr18PP666+/1+z
|
||||
8d5VsDgykEvZ4ZO/6taHroPP/sfOvHSvZM3tL7EzLt5hcFsuC1ZnPJNLJWtvYenqGx/mnnr1P3jCme0M
|
||||
9vMFoGaksTrVHZxZv/3h/9T5l96IRW/wMyvZU2ZVtnsKg0UvJ8Kiejbjwp2tHTvv/61Ye/OjfPJGD4ic
|
||||
UreYf8ehU9Wb7v33btq/jUG9kxdoIyuDy0x+9AAT8J6rnzD99KvaDXf+qyStLofIq9TLWJbtuBUw5cJ/
|
||||
3fQ10xkYQplxhrRVv7pV1e7ngVPO/5eNWNQIdUGxmHrKmhN61Uf+q8QtWc7AEI8a9xa9Qjy2XcFAi/jE
|
||||
PCdH6RTt/q5Tuve3iNfUZJhFzPKBMybole7/r5G8+j6nfpUZsguEHLvcjNJXPlPwnzZdKXL+CfWSg/81
|
||||
U1c/5bZo0oWrEzCtttNKWvFKK3/3fznfyQe5VHINYV6RcO6q1crd+V8hdfMfhfTt/9Syd/yX8+oHetWY
|
||||
FckiY1YJh+Y6zeS137SydvzXjZ53R8y0KpCBwZVbJWDqVrHEHf/ZInf8F07Y8V/Rf9otVtUsjBTJyMBv
|
||||
LyBmXtqpHTHvk27IlGt8KuFuDCK2RhrB0x4rJW3+LxmzARjym/7rBE99wqkQY47sTUYghx2IxRgY+I04
|
||||
xW3yWHnUUoB8LwYm7ghuOc+pvCoRy3lUIxfzqcUsEFSPamIV1NOB6gHpBQNQ2gaFPi8QCwKxKBBLArEU
|
||||
EEtA+cJAWgCIuaGawfkBAATBFuWVyulDAAAAAElFTkSuQmCC
|
||||
</value>
|
||||
</data>
|
||||
<data name="button1.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAYAAAAf8/9hAAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8
|
||||
YQUAAAAgY0hSTQAAeiYAAICEAAD6AAAAgOgAAHUwAADqYAAAOpgAABdwnLpRPAAAAAlwSFlzAAAK/wAA
|
||||
Cv8BNGKaggAAA11JREFUOE8tkYtTVHUUx+8fU5PCUjjlMDT42JB4qcSjoumxk00FG6USapngOrvuDg+B
|
||||
SlYmZQKFxWZyyiBRHBChKMCw5e6CzYagsu+9+4gWVxb49NulO/d353vO/X7P+Z7zk87/uICm7nvKdcM0
|
||||
X/wV0yWZxss2mjplmnptNPdYOdM9TUOPwL3zGDrsFNf+wgHdBB39i0hv1o2g7fRwuHueGP8/q4/hSQKv
|
||||
syq+ImJD4LggxAU+1D3LwU4Hr33+A9Leoz9RdcVNlcXJCmtJycamVgjjIpNUCyTUIsfGKtre+2gtS5Qd
|
||||
v4FUeqyP97vmqLgYSDZ94P2XwZkAN60xrt2L0C+HGbaLnC3EootkQY1wW9n7kPzqfqTiqhtUfuOi8oJD
|
||||
dIiKDrGkzc0RErGQxJ8kUNIJ6zHe6/ibD8z32X9sAKnok2E0ZheadgdrwuJfnjhX70W5Lke4Phukzxbl
|
||||
Z1lhdNrDgivGmqj3zrcPeLdlnvxPryCpK76j+JxM+dkZUX098W52E51Y+ydpOWFm8yR2Eqf47BQfti6S
|
||||
re1BytZcZl/rAiUtM1y1K4K2klxUcmECr4jlJadhmaiYbcD+mDcaZygxybx0QNxCztuXeNk4TaHBwT6T
|
||||
lULdHUrFz4LTMjkmO4UNVor0s+QZJilutJNjnCS3aY699XfY+VY3UlbZBfbofydXP4VakLKFUH1yFnWt
|
||||
zO5TVgp0IxTUTZCnnyD/5G/k1N0lq/YuebpJdrzehZRZ1kXWF1Pk1/wpROOMzM2zrISIB7x4gg9ZCioo
|
||||
yiPcvgh/yH627DpNYa0N9WdTZLzSiZRW0E7mUSsvHpHZXj2KKxwi/VUL6fst+PwhQoEois9JNODE6w6g
|
||||
UhvYXjNGxvEJnk8UyCz5igztGNuqx0mrGScYdvJ0mYWUcguegAMlGEYJLeFVgrgDYZ5RN/Ls4VukHxlF
|
||||
lWtGOnWmj5S8Zl74aAjVx7cJesNsKe0iteg8YW+EZf8KTk8In+LC5/Og2tHCtkMjgiv42V8jifuRdK23
|
||||
Sd3VhkorCvjcOMMBYd9FRHR1ej34I4/wB9yERLw180tSBO+pipuk7hEOEgUS50STsKU+iPHcKCbzLYzm
|
||||
QRrahzC1DVLfNkR9+wCGtjHSdurZmlXPc7uNnGi8xn9S4RHZGLiTUQAAAABJRU5ErkJggg==
|
||||
</value>
|
||||
</data>
|
||||
<data name="button3.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
R0lGODlhFgAVAIMAADJ/x+/3/5rA40qOzrPP6v///1mX0sHY7lGT0PT4/LfS68bb70qUzgAAAAAAAAAA
|
||||
ACH/C05FVFNDQVBFMi4wAwEBAAAh+QQAAAAAACwAAAAAFgAVAAAIdAALCBxIsACAgggTDjyosOFChxAZ
|
||||
QlQocSLCihYLJBCAAAACAQkyJjBg4ACABQgMhJwowIDAgyMFWBxw4KVABQguAtjJs6fPnwlp2iyA02LL
|
||||
kDAHyJw4EoECAARSrmTK0SPIjAQxYjW4taBWrF8zhrU4tkBAADs=
|
||||
</value>
|
||||
</data>
|
||||
</root>
|
@ -1,250 +0,0 @@
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
partial class GpsStatusView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
this.GpsStatusBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.textBox7 = new System.Windows.Forms.TextBox();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.textBox1 = new System.Windows.Forms.TextBox();
|
||||
this.label3 = new System.Windows.Forms.Label();
|
||||
this.textBox2 = new System.Windows.Forms.TextBox();
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.textBox3 = new System.Windows.Forms.TextBox();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.textBox4 = new System.Windows.Forms.TextBox();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
this.button1 = new System.Windows.Forms.Button();
|
||||
this.pictureBox1 = new System.Windows.Forms.PictureBox();
|
||||
((System.ComponentModel.ISupportInitialize)(this.GpsStatusBindingSource)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// GpsStatusBindingSource
|
||||
//
|
||||
this.GpsStatusBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.GpsStatusVm);
|
||||
//
|
||||
// textBox7
|
||||
//
|
||||
this.textBox7.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox7.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsLongitude", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N4"));
|
||||
this.textBox7.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox7.Enabled = false;
|
||||
this.textBox7.Location = new System.Drawing.Point(88, 24);
|
||||
this.textBox7.Name = "textBox7";
|
||||
this.textBox7.ReadOnly = true;
|
||||
this.textBox7.Size = new System.Drawing.Size(53, 13);
|
||||
this.textBox7.TabIndex = 24;
|
||||
this.textBox7.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(4, 24);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(54, 13);
|
||||
this.label1.TabIndex = 25;
|
||||
this.label1.Text = "Longitude";
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(4, 46);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(45, 13);
|
||||
this.label2.TabIndex = 27;
|
||||
this.label2.Text = "Latitude";
|
||||
//
|
||||
// textBox1
|
||||
//
|
||||
this.textBox1.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsLatitude", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N4"));
|
||||
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox1.Enabled = false;
|
||||
this.textBox1.Location = new System.Drawing.Point(88, 46);
|
||||
this.textBox1.Name = "textBox1";
|
||||
this.textBox1.ReadOnly = true;
|
||||
this.textBox1.Size = new System.Drawing.Size(53, 13);
|
||||
this.textBox1.TabIndex = 26;
|
||||
this.textBox1.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(4, 68);
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(42, 13);
|
||||
this.label3.TabIndex = 29;
|
||||
this.label3.Text = "Altitude";
|
||||
//
|
||||
// textBox2
|
||||
//
|
||||
this.textBox2.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox2.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsAltitude", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox2.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox2.Enabled = false;
|
||||
this.textBox2.Location = new System.Drawing.Point(88, 68);
|
||||
this.textBox2.Name = "textBox2";
|
||||
this.textBox2.ReadOnly = true;
|
||||
this.textBox2.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox2.TabIndex = 28;
|
||||
this.textBox2.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(4, 90);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(76, 13);
|
||||
this.label4.TabIndex = 31;
|
||||
this.label4.Text = "Ground Speed";
|
||||
//
|
||||
// textBox3
|
||||
//
|
||||
this.textBox3.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox3.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsGroundSpeed", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N2"));
|
||||
this.textBox3.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox3.Enabled = false;
|
||||
this.textBox3.Location = new System.Drawing.Point(88, 90);
|
||||
this.textBox3.Name = "textBox3";
|
||||
this.textBox3.ReadOnly = true;
|
||||
this.textBox3.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox3.TabIndex = 30;
|
||||
this.textBox3.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(4, 112);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(78, 13);
|
||||
this.label5.TabIndex = 33;
|
||||
this.label5.Text = "Ground Course";
|
||||
//
|
||||
// textBox4
|
||||
//
|
||||
this.textBox4.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsGroundCourse", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.textBox4.Enabled = false;
|
||||
this.textBox4.Location = new System.Drawing.Point(88, 112);
|
||||
this.textBox4.Name = "textBox4";
|
||||
this.textBox4.ReadOnly = true;
|
||||
this.textBox4.Size = new System.Drawing.Size(35, 13);
|
||||
this.textBox4.TabIndex = 32;
|
||||
this.textBox4.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.ForeColor = System.Drawing.Color.Red;
|
||||
this.label6.Location = new System.Drawing.Point(32, 137);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(62, 13);
|
||||
this.label6.TabIndex = 34;
|
||||
this.label6.Text = "No GPS Fix";
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.label7.Location = new System.Drawing.Point(32, 137);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(84, 13);
|
||||
this.label7.TabIndex = 35;
|
||||
this.label7.Text = "GPS Fix Aquired";
|
||||
//
|
||||
// button1
|
||||
//
|
||||
this.button1.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.GpsStatusBindingSource, "GetMapCommand", true));
|
||||
this.button1.Location = new System.Drawing.Point(7, 162);
|
||||
this.button1.Name = "button1";
|
||||
this.button1.Size = new System.Drawing.Size(75, 23);
|
||||
this.button1.TabIndex = 36;
|
||||
this.button1.Text = "Get Map";
|
||||
this.button1.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// pictureBox1
|
||||
//
|
||||
this.pictureBox1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
|
||||
this.pictureBox1.DataBindings.Add(new System.Windows.Forms.Binding("Image", this.GpsStatusBindingSource, "MapImage", true));
|
||||
this.pictureBox1.Location = new System.Drawing.Point(164, 24);
|
||||
this.pictureBox1.Name = "pictureBox1";
|
||||
this.pictureBox1.Size = new System.Drawing.Size(250, 200);
|
||||
this.pictureBox1.TabIndex = 37;
|
||||
this.pictureBox1.TabStop = false;
|
||||
//
|
||||
// GpsStatusView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.pictureBox1);
|
||||
this.Controls.Add(this.button1);
|
||||
this.Controls.Add(this.label7);
|
||||
this.Controls.Add(this.label6);
|
||||
this.Controls.Add(this.label5);
|
||||
this.Controls.Add(this.textBox4);
|
||||
this.Controls.Add(this.label4);
|
||||
this.Controls.Add(this.textBox3);
|
||||
this.Controls.Add(this.label3);
|
||||
this.Controls.Add(this.textBox2);
|
||||
this.Controls.Add(this.label2);
|
||||
this.Controls.Add(this.textBox1);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.textBox7);
|
||||
this.Name = "GpsStatusView";
|
||||
this.Size = new System.Drawing.Size(440, 300);
|
||||
((System.ComponentModel.ISupportInitialize)(this.GpsStatusBindingSource)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.BindingSource GpsStatusBindingSource;
|
||||
private System.Windows.Forms.TextBox textBox7;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private System.Windows.Forms.TextBox textBox1;
|
||||
private System.Windows.Forms.Label label3;
|
||||
private System.Windows.Forms.TextBox textBox2;
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.TextBox textBox3;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.TextBox textBox4;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.Label label7;
|
||||
private System.Windows.Forms.Button button1;
|
||||
private System.Windows.Forms.PictureBox pictureBox1;
|
||||
}
|
||||
}
|
@ -1,34 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
public partial class GpsStatusView : GpsViewDesignable
|
||||
{
|
||||
public GpsStatusView()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
}
|
||||
|
||||
public override void SetDataContext(GpsStatusVm vm)
|
||||
{
|
||||
BindButtons(vm);
|
||||
|
||||
GpsStatusBindingSource.DataSource = vm;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
vm.PropertyChanged += ((sender, e) => GpsStatusBindingSource.ResetBindings(false));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class GpsViewDesignable : ViewCommon<GpsStatusVm> { }
|
||||
}
|
@ -1,123 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="GpsStatusBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
@ -1,147 +0,0 @@
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
partial class MotorCommandsView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.trckBarLeft = new System.Windows.Forms.TrackBar();
|
||||
this.btnStop = new System.Windows.Forms.Button();
|
||||
this.btnSend = new System.Windows.Forms.Button();
|
||||
this.trackBar1 = new System.Windows.Forms.TrackBar();
|
||||
this.trackBar2 = new System.Windows.Forms.TrackBar();
|
||||
this.trackBar3 = new System.Windows.Forms.TrackBar();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trckBarLeft)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trackBar1)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trackBar2)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trackBar3)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// trckBarLeft
|
||||
//
|
||||
this.trckBarLeft.LargeChange = 50;
|
||||
this.trckBarLeft.Location = new System.Drawing.Point(3, 52);
|
||||
this.trckBarLeft.Maximum = 1500;
|
||||
this.trckBarLeft.Minimum = 1000;
|
||||
this.trckBarLeft.Name = "trckBarLeft";
|
||||
this.trckBarLeft.Orientation = System.Windows.Forms.Orientation.Vertical;
|
||||
this.trckBarLeft.Size = new System.Drawing.Size(45, 104);
|
||||
this.trckBarLeft.SmallChange = 10;
|
||||
this.trckBarLeft.TabIndex = 0;
|
||||
this.trckBarLeft.TickFrequency = 50;
|
||||
this.trckBarLeft.Value = 1000;
|
||||
//
|
||||
// btnStop
|
||||
//
|
||||
this.btnStop.Location = new System.Drawing.Point(54, 52);
|
||||
this.btnStop.Name = "btnStop";
|
||||
this.btnStop.Size = new System.Drawing.Size(107, 92);
|
||||
this.btnStop.TabIndex = 4;
|
||||
this.btnStop.Text = "Stop";
|
||||
this.btnStop.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// btnSend
|
||||
//
|
||||
this.btnSend.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.btnSend.Enabled = false;
|
||||
this.btnSend.Location = new System.Drawing.Point(202, 203);
|
||||
this.btnSend.Name = "btnSend";
|
||||
this.btnSend.Size = new System.Drawing.Size(57, 27);
|
||||
this.btnSend.TabIndex = 5;
|
||||
this.btnSend.Text = "Send";
|
||||
this.btnSend.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// trackBar1
|
||||
//
|
||||
this.trackBar1.LargeChange = 50;
|
||||
this.trackBar1.Location = new System.Drawing.Point(180, 52);
|
||||
this.trackBar1.Maximum = 1500;
|
||||
this.trackBar1.Minimum = 1000;
|
||||
this.trackBar1.Name = "trackBar1";
|
||||
this.trackBar1.Orientation = System.Windows.Forms.Orientation.Vertical;
|
||||
this.trackBar1.Size = new System.Drawing.Size(45, 104);
|
||||
this.trackBar1.SmallChange = 10;
|
||||
this.trackBar1.TabIndex = 6;
|
||||
this.trackBar1.TickFrequency = 50;
|
||||
this.trackBar1.Value = 1000;
|
||||
//
|
||||
// trackBar2
|
||||
//
|
||||
this.trackBar2.LargeChange = 50;
|
||||
this.trackBar2.Location = new System.Drawing.Point(57, 150);
|
||||
this.trackBar2.Maximum = 1500;
|
||||
this.trackBar2.Minimum = 1000;
|
||||
this.trackBar2.Name = "trackBar2";
|
||||
this.trackBar2.Size = new System.Drawing.Size(104, 45);
|
||||
this.trackBar2.SmallChange = 10;
|
||||
this.trackBar2.TabIndex = 7;
|
||||
this.trackBar2.TickFrequency = 50;
|
||||
this.trackBar2.Value = 1000;
|
||||
//
|
||||
// trackBar3
|
||||
//
|
||||
this.trackBar3.LargeChange = 50;
|
||||
this.trackBar3.Location = new System.Drawing.Point(54, 3);
|
||||
this.trackBar3.Maximum = 1500;
|
||||
this.trackBar3.Minimum = 1000;
|
||||
this.trackBar3.Name = "trackBar3";
|
||||
this.trackBar3.Size = new System.Drawing.Size(104, 45);
|
||||
this.trackBar3.SmallChange = 10;
|
||||
this.trackBar3.TabIndex = 8;
|
||||
this.trackBar3.TickFrequency = 50;
|
||||
this.trackBar3.Value = 1000;
|
||||
//
|
||||
// MotorCommandsView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.trackBar3);
|
||||
this.Controls.Add(this.trackBar2);
|
||||
this.Controls.Add(this.trackBar1);
|
||||
this.Controls.Add(this.btnSend);
|
||||
this.Controls.Add(this.btnStop);
|
||||
this.Controls.Add(this.trckBarLeft);
|
||||
this.Name = "MotorCommandsView";
|
||||
this.Size = new System.Drawing.Size(262, 233);
|
||||
((System.ComponentModel.ISupportInitialize)(this.trckBarLeft)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trackBar1)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trackBar2)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.trackBar3)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.TrackBar trckBarLeft;
|
||||
private System.Windows.Forms.Button btnStop;
|
||||
private System.Windows.Forms.Button btnSend;
|
||||
private System.Windows.Forms.TrackBar trackBar1;
|
||||
private System.Windows.Forms.TrackBar trackBar2;
|
||||
private System.Windows.Forms.TrackBar trackBar3;
|
||||
}
|
||||
}
|
@ -1,28 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
public partial class MotorCommandsView : MotorCommandsViewDesignable
|
||||
{
|
||||
public MotorCommandsView()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public override void SetDataContext(MotorCommandsVm vm)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class MotorCommandsViewDesignable : ViewCommon<MotorCommandsVm> { }
|
||||
}
|
@ -1,120 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
@ -1,131 +0,0 @@
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
partial class PositionAltitudePidsView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
this.txtSend = new System.Windows.Forms.TextBox();
|
||||
this.button1 = new System.Windows.Forms.Button();
|
||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||
this.positionHoldConfigView1 = new ArducopterConfigurator.Views.PositionHoldConfigView();
|
||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||
this.altitudeHoldConfigView1 = new ArducopterConfigurator.Views.AltitudeHoldConfigView();
|
||||
this.PositionAltitudePidsBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.groupBox1.SuspendLayout();
|
||||
this.groupBox2.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.PositionAltitudePidsBindingSource)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// txtSend
|
||||
//
|
||||
this.txtSend.Location = new System.Drawing.Point(-167, 167);
|
||||
this.txtSend.Name = "txtSend";
|
||||
this.txtSend.Size = new System.Drawing.Size(10, 20);
|
||||
this.txtSend.TabIndex = 4;
|
||||
//
|
||||
// button1
|
||||
//
|
||||
this.button1.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.button1.Location = new System.Drawing.Point(1264, 929);
|
||||
this.button1.Name = "button1";
|
||||
this.button1.Size = new System.Drawing.Size(104, 23);
|
||||
this.button1.TabIndex = 6;
|
||||
this.button1.Text = "Send Command";
|
||||
this.button1.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// groupBox1
|
||||
//
|
||||
this.groupBox1.Controls.Add(this.positionHoldConfigView1);
|
||||
this.groupBox1.Location = new System.Drawing.Point(7, 9);
|
||||
this.groupBox1.Name = "groupBox1";
|
||||
this.groupBox1.Size = new System.Drawing.Size(283, 162);
|
||||
this.groupBox1.TabIndex = 9;
|
||||
this.groupBox1.TabStop = false;
|
||||
this.groupBox1.Text = "Position Hold";
|
||||
//
|
||||
// positionHoldConfigView1
|
||||
//
|
||||
this.positionHoldConfigView1.Location = new System.Drawing.Point(7, 20);
|
||||
this.positionHoldConfigView1.Name = "positionHoldConfigView1";
|
||||
this.positionHoldConfigView1.Size = new System.Drawing.Size(259, 139);
|
||||
this.positionHoldConfigView1.TabIndex = 0;
|
||||
//
|
||||
// groupBox2
|
||||
//
|
||||
this.groupBox2.Controls.Add(this.altitudeHoldConfigView1);
|
||||
this.groupBox2.Location = new System.Drawing.Point(7, 177);
|
||||
this.groupBox2.Name = "groupBox2";
|
||||
this.groupBox2.Size = new System.Drawing.Size(283, 112);
|
||||
this.groupBox2.TabIndex = 10;
|
||||
this.groupBox2.TabStop = false;
|
||||
this.groupBox2.Text = "Altitude Hold";
|
||||
//
|
||||
// altitudeHoldConfigView1
|
||||
//
|
||||
this.altitudeHoldConfigView1.Location = new System.Drawing.Point(7, 20);
|
||||
this.altitudeHoldConfigView1.Name = "altitudeHoldConfigView1";
|
||||
this.altitudeHoldConfigView1.Size = new System.Drawing.Size(270, 91);
|
||||
this.altitudeHoldConfigView1.TabIndex = 0;
|
||||
//
|
||||
// PositionAltitudePidsBindingSource
|
||||
//
|
||||
this.PositionAltitudePidsBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.FlightControlPidsVm);
|
||||
//
|
||||
// PositionAltitudePidsView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.AutoSize = true;
|
||||
this.AutoSizeMode = System.Windows.Forms.AutoSizeMode.GrowAndShrink;
|
||||
this.Controls.Add(this.groupBox2);
|
||||
this.Controls.Add(this.groupBox1);
|
||||
this.Controls.Add(this.button1);
|
||||
this.Controls.Add(this.txtSend);
|
||||
this.Name = "PositionAltitudePidsView";
|
||||
this.Size = new System.Drawing.Size(684, 476);
|
||||
this.groupBox1.ResumeLayout(false);
|
||||
this.groupBox2.ResumeLayout(false);
|
||||
((System.ComponentModel.ISupportInitialize)(this.PositionAltitudePidsBindingSource)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.TextBox txtSend;
|
||||
private System.Windows.Forms.BindingSource PositionAltitudePidsBindingSource;
|
||||
private System.Windows.Forms.Button button1;
|
||||
private System.Windows.Forms.GroupBox groupBox1;
|
||||
private System.Windows.Forms.GroupBox groupBox2;
|
||||
private ArducopterConfigurator.Views.AltitudeHoldConfigView altitudeHoldConfigView1;
|
||||
private ArducopterConfigurator.Views.PositionHoldConfigView positionHoldConfigView1;
|
||||
}
|
||||
}
|
@ -1,36 +0,0 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator
|
||||
{
|
||||
public partial class PositionAltitudePidsView : UserControl, IView<PositionAltitudePidsVm>
|
||||
{
|
||||
private IPresentationModel _vm;
|
||||
|
||||
public PositionAltitudePidsView()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public void SetDataContext(PositionAltitudePidsVm vm)
|
||||
{
|
||||
PositionAltitudePidsBindingSource.DataSource = vm;
|
||||
_vm = vm;
|
||||
|
||||
positionHoldConfigView1.SetDataContext(vm.Vm1);
|
||||
altitudeHoldConfigView1.SetDataContext(vm.Vm2);
|
||||
}
|
||||
|
||||
|
||||
public Control Control
|
||||
{
|
||||
get { return this; }
|
||||
}
|
||||
}
|
||||
}
|
@ -1,123 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="PositionAltitudePidsBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
@ -1,286 +0,0 @@
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
partial class PositionHoldConfigView
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(PositionHoldConfigView));
|
||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.textBox4 = new System.Windows.Forms.TextBox();
|
||||
this.PositionHoldConfigBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.textBox5 = new System.Windows.Forms.TextBox();
|
||||
this.textBox6 = new System.Windows.Forms.TextBox();
|
||||
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
||||
this.label3 = new System.Windows.Forms.Label();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.textBox3 = new System.Windows.Forms.TextBox();
|
||||
this.textBox2 = new System.Windows.Forms.TextBox();
|
||||
this.textBox1 = new System.Windows.Forms.TextBox();
|
||||
this.textBox7 = new System.Windows.Forms.TextBox();
|
||||
this.textBox8 = new System.Windows.Forms.TextBox();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
this.label8 = new System.Windows.Forms.Label();
|
||||
this.btnRefresh = new System.Windows.Forms.Button();
|
||||
this.groupBox2.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.PositionHoldConfigBindingSource)).BeginInit();
|
||||
this.groupBox3.SuspendLayout();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// groupBox2
|
||||
//
|
||||
this.groupBox2.Controls.Add(this.label4);
|
||||
this.groupBox2.Controls.Add(this.label5);
|
||||
this.groupBox2.Controls.Add(this.label6);
|
||||
this.groupBox2.Controls.Add(this.textBox4);
|
||||
this.groupBox2.Controls.Add(this.textBox5);
|
||||
this.groupBox2.Controls.Add(this.textBox6);
|
||||
this.groupBox2.Location = new System.Drawing.Point(91, 3);
|
||||
this.groupBox2.Name = "groupBox2";
|
||||
this.groupBox2.Size = new System.Drawing.Size(83, 101);
|
||||
this.groupBox2.TabIndex = 12;
|
||||
this.groupBox2.TabStop = false;
|
||||
this.groupBox2.Text = "Pitch";
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(7, 74);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(15, 13);
|
||||
this.label4.TabIndex = 5;
|
||||
this.label4.Text = "D";
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(7, 48);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(10, 13);
|
||||
this.label5.TabIndex = 4;
|
||||
this.label5.Text = "I";
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(7, 22);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(14, 13);
|
||||
this.label6.TabIndex = 3;
|
||||
this.label6.Text = "P";
|
||||
//
|
||||
// textBox4
|
||||
//
|
||||
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "PitchD", true));
|
||||
this.textBox4.Location = new System.Drawing.Point(23, 71);
|
||||
this.textBox4.Name = "textBox4";
|
||||
this.textBox4.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox4.TabIndex = 2;
|
||||
//
|
||||
// PositionHoldConfigBindingSource
|
||||
//
|
||||
this.PositionHoldConfigBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.PositionHoldConfigVm);
|
||||
this.PositionHoldConfigBindingSource.Sort = "";
|
||||
//
|
||||
// textBox5
|
||||
//
|
||||
this.textBox5.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "PitchI", true));
|
||||
this.textBox5.Location = new System.Drawing.Point(23, 45);
|
||||
this.textBox5.Name = "textBox5";
|
||||
this.textBox5.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox5.TabIndex = 1;
|
||||
//
|
||||
// textBox6
|
||||
//
|
||||
this.textBox6.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "PitchP", true));
|
||||
this.textBox6.Location = new System.Drawing.Point(23, 19);
|
||||
this.textBox6.Name = "textBox6";
|
||||
this.textBox6.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox6.TabIndex = 0;
|
||||
//
|
||||
// groupBox3
|
||||
//
|
||||
this.groupBox3.Controls.Add(this.label3);
|
||||
this.groupBox3.Controls.Add(this.label2);
|
||||
this.groupBox3.Controls.Add(this.label1);
|
||||
this.groupBox3.Controls.Add(this.textBox3);
|
||||
this.groupBox3.Controls.Add(this.textBox2);
|
||||
this.groupBox3.Controls.Add(this.textBox1);
|
||||
this.groupBox3.Location = new System.Drawing.Point(3, 3);
|
||||
this.groupBox3.Name = "groupBox3";
|
||||
this.groupBox3.Size = new System.Drawing.Size(82, 101);
|
||||
this.groupBox3.TabIndex = 11;
|
||||
this.groupBox3.TabStop = false;
|
||||
this.groupBox3.Text = "Roll";
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(7, 74);
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(15, 13);
|
||||
this.label3.TabIndex = 5;
|
||||
this.label3.Text = "D";
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(7, 48);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(10, 13);
|
||||
this.label2.TabIndex = 4;
|
||||
this.label2.Text = "I";
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(7, 22);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(14, 13);
|
||||
this.label1.TabIndex = 3;
|
||||
this.label1.Text = "P";
|
||||
//
|
||||
// textBox3
|
||||
//
|
||||
this.textBox3.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "RollD", true));
|
||||
this.textBox3.Location = new System.Drawing.Point(23, 71);
|
||||
this.textBox3.Name = "textBox3";
|
||||
this.textBox3.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox3.TabIndex = 2;
|
||||
//
|
||||
// textBox2
|
||||
//
|
||||
this.textBox2.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "RollI", true));
|
||||
this.textBox2.Location = new System.Drawing.Point(23, 45);
|
||||
this.textBox2.Name = "textBox2";
|
||||
this.textBox2.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox2.TabIndex = 1;
|
||||
//
|
||||
// textBox1
|
||||
//
|
||||
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "RollP", true));
|
||||
this.textBox1.Location = new System.Drawing.Point(23, 19);
|
||||
this.textBox1.Name = "textBox1";
|
||||
this.textBox1.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox1.TabIndex = 0;
|
||||
//
|
||||
// textBox7
|
||||
//
|
||||
this.textBox7.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "MaximumAngle", true));
|
||||
this.textBox7.Location = new System.Drawing.Point(179, 22);
|
||||
this.textBox7.Name = "textBox7";
|
||||
this.textBox7.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox7.TabIndex = 13;
|
||||
//
|
||||
// textBox8
|
||||
//
|
||||
this.textBox8.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.PositionHoldConfigBindingSource, "GeoCorrectionFactor", true, System.Windows.Forms.DataSourceUpdateMode.OnPropertyChanged));
|
||||
this.textBox8.Location = new System.Drawing.Point(179, 75);
|
||||
this.textBox8.Name = "textBox8";
|
||||
this.textBox8.Size = new System.Drawing.Size(50, 20);
|
||||
this.textBox8.TabIndex = 14;
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(180, 6);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(60, 13);
|
||||
this.label7.TabIndex = 15;
|
||||
this.label7.Text = "Max Angle:";
|
||||
//
|
||||
// label8
|
||||
//
|
||||
this.label8.AutoSize = true;
|
||||
this.label8.Location = new System.Drawing.Point(176, 48);
|
||||
this.label8.Name = "label8";
|
||||
this.label8.Size = new System.Drawing.Size(81, 26);
|
||||
this.label8.TabIndex = 16;
|
||||
this.label8.Text = "Geo Correction \r\nFactor:";
|
||||
this.label8.Click += new System.EventHandler(this.label8_Click);
|
||||
//
|
||||
// btnRefresh
|
||||
//
|
||||
this.btnRefresh.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.PositionHoldConfigBindingSource, "RefreshCommand", true));
|
||||
this.btnRefresh.Image = ((System.Drawing.Image)(resources.GetObject("btnRefresh.Image")));
|
||||
this.btnRefresh.Location = new System.Drawing.Point(203, 110);
|
||||
this.btnRefresh.Name = "btnRefresh";
|
||||
this.btnRefresh.Size = new System.Drawing.Size(26, 26);
|
||||
this.btnRefresh.TabIndex = 18;
|
||||
this.btnRefresh.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// PositionHoldConfigView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.btnRefresh);
|
||||
this.Controls.Add(this.label8);
|
||||
this.Controls.Add(this.label7);
|
||||
this.Controls.Add(this.textBox8);
|
||||
this.Controls.Add(this.textBox7);
|
||||
this.Controls.Add(this.groupBox2);
|
||||
this.Controls.Add(this.groupBox3);
|
||||
this.Name = "PositionHoldConfigView";
|
||||
this.Size = new System.Drawing.Size(259, 139);
|
||||
this.groupBox2.ResumeLayout(false);
|
||||
this.groupBox2.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.PositionHoldConfigBindingSource)).EndInit();
|
||||
this.groupBox3.ResumeLayout(false);
|
||||
this.groupBox3.PerformLayout();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.GroupBox groupBox2;
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.TextBox textBox4;
|
||||
private System.Windows.Forms.TextBox textBox5;
|
||||
private System.Windows.Forms.TextBox textBox6;
|
||||
private System.Windows.Forms.GroupBox groupBox3;
|
||||
private System.Windows.Forms.Label label3;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private System.Windows.Forms.TextBox textBox3;
|
||||
private System.Windows.Forms.TextBox textBox2;
|
||||
private System.Windows.Forms.TextBox textBox1;
|
||||
private System.Windows.Forms.TextBox textBox7;
|
||||
private System.Windows.Forms.TextBox textBox8;
|
||||
private System.Windows.Forms.Label label7;
|
||||
private System.Windows.Forms.Label label8;
|
||||
private System.Windows.Forms.BindingSource PositionHoldConfigBindingSource;
|
||||
private System.Windows.Forms.Button btnRefresh;
|
||||
}
|
||||
}
|
@ -1,36 +0,0 @@
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Text;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
|
||||
namespace ArducopterConfigurator.Views
|
||||
{
|
||||
public partial class PositionHoldConfigView : PositionHoldConfigViewDesignable
|
||||
{
|
||||
public PositionHoldConfigView()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
}
|
||||
|
||||
public override void SetDataContext(PositionHoldConfigVm vm)
|
||||
{
|
||||
BindButtons(vm);
|
||||
|
||||
|
||||
PositionHoldConfigBindingSource.DataSource = vm;
|
||||
|
||||
if (Program.IsMonoRuntime)
|
||||
vm.PropertyChanged += ((sender, e) => PositionHoldConfigBindingSource.ResetBindings(false));
|
||||
}
|
||||
|
||||
private void label8_Click(object sender, System.EventArgs e)
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
// Required for VS2008 designer. No functional value
|
||||
public class PositionHoldConfigViewDesignable : ViewCommon<PositionHoldConfigVm> { }
|
||||
}
|
@ -1,143 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="PositionHoldConfigBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="btnRefresh.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAYAAAAf8/9hAAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8
|
||||
YQUAAAAgY0hSTQAAeiYAAICEAAD6AAAAgOgAAHUwAADqYAAAOpgAABdwnLpRPAAAAAlwSFlzAAAOwQAA
|
||||
DsEBuJFr7QAAAtVJREFUOE9jYKAaiN/PweB3RIohcL8MGIPYIDFigVbd+cTIeXfuxS+5+yQWiCPn3X4o
|
||||
X3Y2EaRfMOOojkbN2XKprCMGOM2TyDoakrfm3tcZ59/+nw7EnQef/dGqPJnKELhTLHzGtcNzT77+X7Hh
|
||||
wQXdsuOeDAz1TKgGWazktG87M6dx95P/vcde/u8/8ep/4Zo772Sz9tsw+K8X8Oo9N7Nr18PP666+/1+z
|
||||
8d5VsDgykEvZ4ZO/6taHroPP/sfOvHSvZM3tL7EzLt5hcFsuC1ZnPJNLJWtvYenqGx/mnnr1P3jCme0M
|
||||
9vMFoGaksTrVHZxZv/3h/9T5l96IRW/wMyvZU2ZVtnsKg0UvJ8Kiejbjwp2tHTvv/61Ye/OjfPJGD4ic
|
||||
UreYf8ehU9Wb7v33btq/jUG9kxdoIyuDy0x+9AAT8J6rnzD99KvaDXf+qyStLofIq9TLWJbtuBUw5cJ/
|
||||
3fQ10xkYQplxhrRVv7pV1e7ngVPO/5eNWNQIdUGxmHrKmhN61Uf+q8QtWc7AEI8a9xa9Qjy2XcFAi/jE
|
||||
PCdH6RTt/q5Tuve3iNfUZJhFzPKBMybole7/r5G8+j6nfpUZsguEHLvcjNJXPlPwnzZdKXL+CfWSg/81
|
||||
U1c/5bZo0oWrEzCtttNKWvFKK3/3fznfyQe5VHINYV6RcO6q1crd+V8hdfMfhfTt/9Syd/yX8+oHetWY
|
||||
FckiY1YJh+Y6zeS137SydvzXjZ53R8y0KpCBwZVbJWDqVrHEHf/ZInf8F07Y8V/Rf9otVtUsjBTJyMBv
|
||||
LyBmXtqpHTHvk27IlGt8KuFuDCK2RhrB0x4rJW3+LxmzARjym/7rBE99wqkQY47sTUYghx2IxRgY+I04
|
||||
xW3yWHnUUoB8LwYm7ghuOc+pvCoRy3lUIxfzqcUsEFSPamIV1NOB6gHpBQNQ2gaFPi8QCwKxKBBLArEU
|
||||
EEtA+cJAWgCIuaGawfkBAATBFuWVyulDAAAAAElFTkSuQmCC
|
||||
</value>
|
||||
</data>
|
||||
</root>
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user