This commit is contained in:
James Goppert 2011-11-27 23:56:17 -05:00
commit fcb4d9cb15
191 changed files with 13607 additions and 29931 deletions

2
.gitignore vendored
View File

@ -18,4 +18,6 @@ build
/Tools/ArdupilotMegaPlanner/resedit/bin
/Tools/ArdupilotMegaPlanner/resedit/obj
tags
*.o
.*.swp
.*.swo

View File

@ -7,8 +7,6 @@
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
//#define HIL_MODE HIL_MODE_ATTITUDE
//#define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
#define FRAME_CONFIG QUAD_FRAME
/*
options:
@ -65,3 +63,5 @@
#define USERHOOK_VARIABLES "UserVariables.h"
// enable this for the new 'APM2' hardware
// #define CONFIG_APM_HARDWARE APM_HARDWARE_APM2

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V2.0.51"
#define THISFIRMWARE "ArduCopter V2.1.0 Alpha"
/*
ArduCopter Version 2.0 Beta
Authors: Jason Short
@ -49,16 +49,23 @@ And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <AP_GPS.h> // ArduPilot GPS library
#include <Wire.h> // Arduino I2C lib
#include <SPI.h> // Arduino SPI lib
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
#include <AP_AnalogSource.h>
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
#include <AP_IMU.h> // ArduPilot Mega IMU Library
#include <AP_PeriodicProcess.h> // Parent header of Timer and TimerAperiodic
// (only included for makefile libpath to work)
#include <AP_TimerProcess.h> // TimerProcess is the scheduler for MPU6000 reads.
#include <AP_TimerAperiodicProcess.h> // TimerAperiodicProcess is the scheduler for ADC reads.
#include <AP_DCM.h> // ArduPilot Mega DCM Library
#include <APM_PI.h> // PI library
#include <RC_Channel.h> // RC Channel Library
@ -89,6 +96,8 @@ FastSerialPort0(Serial); // FTDI/console
FastSerialPort1(Serial1); // GPS port
FastSerialPort3(Serial3); // Telemetry port
Arduino_Mega_ISR_Registry isr_registry;
////////////////////////////////////////////////////////////////////////////////
// Parameters
////////////////////////////////////////////////////////////////////////////////
@ -102,6 +111,24 @@ static Parameters g;
// prototypes
static void update_events(void);
////////////////////////////////////////////////////////////////////////////////
// RC Hardware
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
APM_RC_APM2 APM_RC;
#else
APM_RC_APM1 APM_RC;
#endif
////////////////////////////////////////////////////////////////////////////////
// Dataflash
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
DataFlash_APM2 DataFlash;
#else
DataFlash_APM1 DataFlash;
#endif
////////////////////////////////////////////////////////////////////////////////
// Sensors
@ -125,9 +152,17 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#if HIL_MODE == HIL_MODE_DISABLED
// real sensors
#if CONFIG_ADC == ENABLED
AP_ADC_ADS7844 adc;
#endif
#ifdef DESKTOP_BUILD
APM_BMP085_HIL_Class barometer;
AP_Compass_HIL compass;
#else
APM_BMP085_Class barometer;
AP_Compass_HMC5843 compass(Parameters::k_param_compass);
#endif
#ifdef OPTFLOW_ENABLED
AP_OpticalFlow_ADNS3080 optflow;
@ -159,12 +194,27 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#error Unrecognised GPS_PROTOCOL setting.
#endif // GPS PROTOCOL
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN );
#else
AP_InertialSensor_Oilpan ins(&adc);
#endif
AP_IMU_INS imu(&ins, Parameters::k_param_IMU_calibration);
AP_DCM dcm(&imu, g_gps);
AP_TimerProcess timer_scheduler;
#elif HIL_MODE == HIL_MODE_SENSORS
// sensor emulators
AP_ADC_HIL adc;
APM_BMP085_HIL_Class barometer;
AP_Compass_HIL compass;
AP_GPS_HIL g_gps_driver(NULL);
AP_IMU_Shim imu;
AP_DCM dcm(&imu, g_gps);
AP_PeriodicProcessStub timer_scheduler;
AP_InertialSensor_Stub ins;
static int32_t gps_base_alt;
#elif HIL_MODE == HIL_MODE_ATTITUDE
AP_ADC_HIL adc;
@ -172,6 +222,8 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
AP_GPS_HIL g_gps_driver(NULL);
AP_Compass_HIL compass; // never used
AP_IMU_Shim imu; // never used
AP_InertialSensor_Stub ins;
AP_PeriodicProcessStub timer_scheduler;
#ifdef OPTFLOW_ENABLED
AP_OpticalFlow_ADNS3080 optflow;
#endif
@ -180,17 +232,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#error Unrecognised HIL_MODE setting.
#endif // HIL MODE
#if HIL_MODE != HIL_MODE_ATTITUDE
#if HIL_MODE != HIL_MODE_SENSORS
// Normal
AP_IMU_Oilpan imu(&adc, Parameters::k_param_IMU_calibration);
#else
// hil imu
AP_IMU_Shim imu;
#endif
// normal dcm
AP_DCM dcm(&imu, g_gps);
#endif
////////////////////////////////////////////////////////////////////////////////
// GCS selection
@ -203,12 +245,21 @@ GCS_MAVLINK gcs3(Parameters::k_param_streamrates_port3);
////////////////////////////////////////////////////////////////////////////////
//
ModeFilter sonar_mode_filter;
#if CONFIG_SONAR == ENABLED
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
AP_AnalogSource_ADC sonar_analog_source( &adc,
CONFIG_SONAR_SOURCE_ADC_CHANNEL, 0.25);
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
AP_AnalogSource_Arduino sonar_analog_source(CONFIG_SONAR_SOURCE_ANALOG_PIN);
#endif
#if SONAR_TYPE == MAX_SONAR_XL
AP_RangeFinder_MaxsonarXL sonar(&adc, &sonar_mode_filter);//(SONAR_PORT, &adc);
AP_RangeFinder_MaxsonarXL sonar(&sonar_analog_source, &sonar_mode_filter);
#else
#error Unrecognised SONAR_TYPE setting.
#endif
#endif
// agmatthews USERHOOKS
////////////////////////////////////////////////////////////////////////////////
@ -508,6 +559,11 @@ static bool new_radio_frame;
AP_Relay relay;
#if USB_MUX_PIN > 0
static bool usb_connected;
#endif
////////////////////////////////////////////////////////////////////////////////
// Top-level logic
////////////////////////////////////////////////////////////////////////////////
@ -768,9 +824,12 @@ static void fifty_hz_loop()
// Read Sonar
// ----------
# if CONFIG_SONAR == ENABLED
if(g.sonar_enabled){
sonar_alt = sonar.read();
}
#endif
// agmatthews - USERHOOKS
#ifdef USERHOOK_50HZLOOP
USERHOOK_50HZLOOP
@ -864,6 +923,9 @@ static void slow_loop()
update_motor_leds();
#endif
#if USB_MUX_PIN > 0
check_usb_mux();
#endif
break;
default:
@ -1260,17 +1322,9 @@ static void update_altitude()
baro_alt = (baro_alt + read_barometer()) >> 1;
// calc the vertical accel rate
#if CLIMB_RATE_BARO == 0
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 2; // invert and scale
temp_baro_alt = (float)temp_baro_alt * .1 + (float)old_baro_alt * .9;
baro_rate = (temp_baro_alt - old_baro_alt) * 10;
old_baro_alt = temp_baro_alt;
#else
baro_rate = (baro_alt - old_baro_alt) * 10;
int temp = (baro_alt - old_baro_alt) * 10;
baro_rate = (temp + baro_rate) >> 1;
old_baro_alt = baro_alt;
#endif
// sonar_alt is calculaed in a faster loop and filtered with a mode filter
#endif

View File

@ -40,7 +40,10 @@ public:
///
/// @param port The stream over which messages are exchanged.
///
void init(FastSerial *port) { _port = port; }
void init(FastSerial *port) {
_port = port;
initialised = true;
}
/// Update GCS state.
///
@ -83,6 +86,9 @@ public:
// send streams which match frequency range
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
// set to true if this GCS link is active
bool initialised;
protected:
/// The stream we are communicating over
FastSerial *_port;

View File

@ -29,7 +29,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{
mavlink_msg_heartbeat_send(
chan,
mavlink_system.type,
2 /*mavlink_system.type*/, //MAV_TYPE_QUADROTOR
MAV_AUTOPILOT_ARDUPILOTMEGA);
}
@ -1383,27 +1383,32 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// handle variables with standard type IDs
if (var_type == AP_Var::k_typeid_float) {
((AP_Float *)vp)->set_and_save(packet.param_value);
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(1, (float)((AP_Float *)vp)->get());
#endif
} else if (var_type == AP_Var::k_typeid_float16) {
((AP_Float16 *)vp)->set_and_save(packet.param_value);
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(2, (float)((AP_Float *)vp)->get());
#endif
} else if (var_type == AP_Var::k_typeid_int32) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(3, (int32_t)((AP_Float *)vp)->get());
#endif
} else if (var_type == AP_Var::k_typeid_int16) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition);
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(4, (int32_t)((AP_Float *)vp)->get());
#endif
} else if (var_type == AP_Var::k_typeid_int8) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(5, (int32_t)((AP_Float *)vp)->get());
#endif
} else {
// we don't support mavlink set on this parameter
break;
@ -1653,6 +1658,7 @@ GCS_MAVLINK::queued_param_send()
value = vp->cast_to_float();
if (!isnan(value)) {
char param_name[ONBOARD_PARAM_NAME_LENGTH]; /// XXX HACK
memset(param_name, 0, sizeof(param_name));
vp->copy_name(param_name, sizeof(param_name));
mavlink_msg_param_value_send(
@ -1716,6 +1722,9 @@ static void mavlink_delay(unsigned long t)
gcs_update();
}
delay(1);
#if USB_MUX_PIN > 0
check_usb_mux();
#endif
} while (millis() - tstart < t);
in_mavlink_delay = false;
@ -1727,8 +1736,10 @@ static void mavlink_delay(unsigned long t)
static void gcs_send_message(enum ap_message id)
{
gcs0.send_message(id);
if (gcs3.initialised) {
gcs3.send_message(id);
}
}
/*
send data streams in the given rate range on both links
@ -1736,8 +1747,10 @@ static void gcs_send_message(enum ap_message id)
static void gcs_data_stream_send(uint16_t freqMin, uint16_t freqMax)
{
gcs0.data_stream_send(freqMin, freqMax);
if (gcs3.initialised) {
gcs3.data_stream_send(freqMin, freqMax);
}
}
/*
look for incoming commands on the GCS links
@ -1745,20 +1758,26 @@ static void gcs_data_stream_send(uint16_t freqMin, uint16_t freqMax)
static void gcs_update(void)
{
gcs0.update();
if (gcs3.initialised) {
gcs3.update();
}
}
static void gcs_send_text(gcs_severity severity, const char *str)
{
gcs0.send_text(severity, str);
if (gcs3.initialised) {
gcs3.send_text(severity, str);
}
}
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
{
gcs0.send_text(severity, str);
if (gcs3.initialised) {
gcs3.send_text(severity, str);
}
}
/*
send a low priority formatted message to the GCS

View File

@ -53,7 +53,9 @@ print_log_menu(void)
{
int log_start;
int log_end;
byte last_log_num = get_num_logs();
int temp;
uint16_t num_logs = get_num_logs();
Serial.printf_P(PSTR("logs enabled: "));
@ -75,15 +77,20 @@ print_log_menu(void)
Serial.println();
if (last_log_num == 0) {
Serial.printf_P(PSTR("\nNo logs\nType 'dump 0'.\n\n"));
if (num_logs == 0) {
Serial.printf_P(PSTR("\nNo logs\n\n"));
}else{
Serial.printf_P(PSTR("\n%d logs\n"), last_log_num);
Serial.printf_P(PSTR("\n%d logs\n"), num_logs);
for(int i = 1; i < last_log_num + 1; i++) {
get_log_boundaries(i, log_start, log_end);
//Serial.printf_P(PSTR("last_num %d "), last_log_num);
Serial.printf_P(PSTR("Log # %d, start %d, end %d\n"), i, log_start, log_end);
for(int i=num_logs;i>=1;i--) {
int last_log_start = log_start, last_log_end = log_end;
temp = g.log_last_filenumber-i+1;
get_log_boundaries(temp, log_start, log_end);
Serial.printf_P(PSTR("Log %d, start %d, end %d\n"), temp, log_start, log_end);
if (last_log_start == log_start && last_log_end == log_end) {
// we are printing bogus logs
break;
}
}
Serial.println();
}
@ -93,17 +100,20 @@ print_log_menu(void)
static int8_t
dump_log(uint8_t argc, const Menu::arg *argv)
{
byte dump_log;
int dump_log;
int dump_log_start;
int dump_log_end;
byte last_log_num;
// check that the requested log number can be read
dump_log = argv[1].i;
if (/*(argc != 2) || */ (dump_log < 1)) {
Serial.printf_P(PSTR("bad log # %d\n"), dump_log);
Log_Read(0, 4095);
erase_logs(NULL, NULL);
last_log_num = g.log_last_filenumber;
if (dump_log == -1) {
Serial.printf_P(PSTR("dumping all\n"));
Log_Read(1, DF_LAST_PAGE);
return(-1);
} else if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
Serial.printf_P(PSTR("bad log number\n"));
return(-1);
}
@ -121,31 +131,17 @@ dump_log(uint8_t argc, const Menu::arg *argv)
static int8_t
erase_logs(uint8_t argc, const Menu::arg *argv)
{
//for(int i = 10 ; i > 0; i--) {
// Serial.printf_P(PSTR("ATTENTION - Erasing log in %d seconds.\n"), i);
// delay(1000);
//}
// lay down a bunch of "log end" messages.
Serial.printf_P(PSTR("\nErasing log...\n"));
for(int j = 1; j < 4096; j++)
DataFlash.SetFileNumber(0xFFFF);
for(int j = 1; j <= DF_LAST_PAGE; j++) {
DataFlash.PageErase(j);
clear_header();
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
}
g.log_last_filenumber.set_and_save(0);
Serial.printf_P(PSTR("\nLog erased.\n"));
return (0);
}
static void clear_header()
{
DataFlash.StartWrite(1);
DataFlash.WriteByte(HEAD_BYTE1);
DataFlash.WriteByte(HEAD_BYTE2);
DataFlash.WriteByte(LOG_INDEX_MSG);
DataFlash.WriteByte(0);
DataFlash.WriteByte(END_BYTE);
DataFlash.FinishWrite();
return 0;
}
static int8_t
@ -202,158 +198,203 @@ process_logs(uint8_t argc, const Menu::arg *argv)
}
// finds out how many logs are available
// This function determines the number of whole or partial log files in the DataFlash
// Wholly overwritten files are (of course) lost.
static byte get_num_logs(void)
{
int page = 1;
byte data;
byte log_step = 0;
uint16_t lastpage;
uint16_t last;
uint16_t first;
if(g.log_last_filenumber < 1) return 0;
DataFlash.StartRead(1);
if(DataFlash.GetFileNumber() == 0XFFFF) return 0;
while (page == 1) {
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++;
break;
case 1:
if(data==HEAD_BYTE2) // Head byte 2
log_step++;
else
log_step = 0;
break;
case 2:
if(data == LOG_INDEX_MSG){
byte num_logs = DataFlash.ReadByte();
//Serial.printf("num_logs, %d\n", num_logs);
return num_logs;
}else{
//Serial.printf("* %d\n", data);
log_step = 0; // Restart, we have a problem...
}
break;
}
page = DataFlash.GetPage();
lastpage = find_last();
DataFlash.StartRead(lastpage);
last = DataFlash.GetFileNumber();
DataFlash.StartRead(lastpage + 2);
first = DataFlash.GetFileNumber();
if(first > last) {
DataFlash.StartRead(1);
first = DataFlash.GetFileNumber();
}
if(last == first)
{
return 1;
} else {
return (last - first + 1);
}
return 0;
}
// send the number of the last log?
// This function starts a new log file in the DataFlash
static void start_new_log()
{
byte num_existing_logs = get_num_logs();
uint16_t last_page;
int start_pages[50] = {0,0,0};
int end_pages[50] = {0,0,0};
if(num_existing_logs > 0){
for(int i = 0; i < num_existing_logs; i++) {
get_log_boundaries(i + 1, start_pages[i], end_pages[i]);
}
end_pages[num_existing_logs - 1] = find_last_log_page(start_pages[num_existing_logs - 1]);
}
if(num_existing_logs == 0 ||
((end_pages[num_existing_logs - 1] < 4095) && (num_existing_logs < MAX_NUM_LOGS /*50*/))) {
if(num_existing_logs > 0)
start_pages[num_existing_logs] = end_pages[num_existing_logs - 1] + 1;
else
start_pages[0] = 2;
num_existing_logs++;
DataFlash.StartWrite(1);
DataFlash.WriteByte(HEAD_BYTE1);
DataFlash.WriteByte(HEAD_BYTE2);
DataFlash.WriteByte(LOG_INDEX_MSG);
DataFlash.WriteByte(num_existing_logs);
for(int i = 0; i < MAX_NUM_LOGS; i++) {
DataFlash.WriteInt(start_pages[i]);
DataFlash.WriteInt(end_pages[i]);
}
DataFlash.WriteByte(END_BYTE);
DataFlash.FinishWrite();
DataFlash.StartWrite(start_pages[num_existing_logs - 1]);
}else{
gcs_send_text_P(SEVERITY_LOW,PSTR("Logs full"));
if(g.log_last_filenumber < 1) {
last_page = 0;
} else {
last_page = find_last();
}
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
DataFlash.SetFileNumber(g.log_last_filenumber);
DataFlash.StartWrite(last_page + 1);
}
// All log data is stored in page 1?
// This function finds the first and last pages of a log file
// The first page may be greater than the last page if the DataFlash has been filled and partially overwritten.
static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
{
int page = 1;
byte data;
byte log_step = 0;
int num = get_num_logs();
int look;
if(num == 1)
{
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
{
start_page = 1;
end_page = find_last_log_page((uint16_t)log_num);
} else {
end_page = find_last_log_page((uint16_t)log_num);
start_page = end_page + 1;
}
DataFlash.StartRead(1);
while (page == 1) {
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++;
break;
case 1:
if(data==HEAD_BYTE2) // Head byte 2
log_step++;
else
log_step = 0;
break;
case 2:
if(data==LOG_INDEX_MSG){
byte num_logs = DataFlash.ReadByte();
for(int i=0;i<log_num;i++) {
start_page = DataFlash.ReadInt();
end_page = DataFlash.ReadInt();
}
if(log_num==num_logs)
end_page = find_last_log_page(start_page);
return; // This is the normal exit point
}else{
log_step=0; // Restart, we have a problem...
}
break;
} else {
if(log_num==1) {
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF) {
start_page = 1;
} else {
start_page = find_last() + 1;
}
page = DataFlash.GetPage();
} else {
if(log_num == g.log_last_filenumber - num + 1) {
start_page = find_last() + 1;
} else {
look = log_num-1;
do {
start_page = find_last_log_page(look) + 1;
look--;
} while (start_page <= 0);
}
}
}
// Error condition if we reach here with page = 2 TO DO - report condition
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
end_page = find_last_log_page((uint16_t)log_num);
if(end_page <= 0) end_page = start_page;
}
//
static int find_last_log_page(int bottom_page)
static bool check_wrapped(void)
{
int top_page = 4096;
int look_page;
int32_t check;
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
check = DataFlash.ReadLong();
//Serial.printf("look page:%d, check:%d\n", look_page, check);
if(check == -1L)
top_page = look_page;
else
bottom_page = look_page;
}
return top_page;
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
return 0;
else
return 1;
}
// This function finds the last page of the last file
static int find_last(void)
{
uint16_t look;
uint16_t bottom = 1;
uint16_t top = DF_LAST_PAGE;
uint32_t look_hash;
uint32_t bottom_hash;
uint32_t top_hash;
DataFlash.StartRead(bottom);
bottom_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
while(top-bottom > 1)
{
look = (top+bottom)/2;
DataFlash.StartRead(look);
look_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
if (look_hash >= 0xFFFF0000) look_hash = 0;
if(look_hash < bottom_hash) {
// move down
top = look;
} else {
// move up
bottom = look;
bottom_hash = look_hash;
}
}
DataFlash.StartRead(top);
top_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
if (top_hash >= 0xFFFF0000) top_hash = 0;
if (top_hash > bottom_hash)
{
return top;
} else {
return bottom;
}
}
// This function finds the last page of a particular log file
static int find_last_log_page(uint16_t log_number)
{
uint16_t look;
uint16_t bottom;
uint16_t top;
uint32_t look_hash;
uint32_t check_hash;
if(check_wrapped())
{
DataFlash.StartRead(1);
bottom = DataFlash.GetFileNumber();
if (bottom > log_number)
{
bottom = find_last();
top = DF_LAST_PAGE;
} else {
bottom = 1;
top = find_last();
}
} else {
bottom = 1;
top = find_last();
}
check_hash = (long)log_number<<16 | 0xFFFF;
while(top-bottom > 1)
{
look = (top+bottom)/2;
DataFlash.StartRead(look);
look_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
if (look_hash >= 0xFFFF0000) look_hash = 0;
if(look_hash > check_hash) {
// move down
top = look;
} else {
// move up
bottom = look;
}
}
DataFlash.StartRead(top);
if (DataFlash.GetFileNumber() == log_number) return top;
DataFlash.StartRead(bottom);
if (DataFlash.GetFileNumber() == log_number) return bottom;
return -1;
}
// Write an GPS packet. Total length : 30 bytes
static void Log_Write_GPS()
{
@ -924,13 +965,36 @@ static void Log_Read_Data()
Serial.printf_P(PSTR("DATA: %d, %ld\n"), temp1, temp2);
}
// Read the DataFlash log memory
static void Log_Read(int start_page, int end_page)
{
int packet_count = 0;
#ifdef AIRFRAME_NAME
Serial.printf_P(PSTR((AIRFRAME_NAME)
#endif
Serial.printf_P(PSTR("\n" THISFIRMWARE
"\nFree RAM: %u\n"),
memcheck_available_memory());
if(start_page > end_page)
{
packet_count = Log_Read_Process(start_page, DF_LAST_PAGE);
packet_count += Log_Read_Process(1, end_page);
} else {
packet_count = Log_Read_Process(start_page, end_page);
}
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count);
}
// Read the DataFlash log memory : Packet Parser
static void Log_Read(int start_page, int end_page)
static int Log_Read_Process(int start_page, int end_page)
{
byte data;
byte log_step = 0;
int page = start_page;
int packet_count = 0;
DataFlash.StartRead(start_page);
@ -1010,9 +1074,18 @@ static void Log_Read(int start_page, int end_page)
break;
}
break;
case 3:
if(data == END_BYTE){
packet_count++;
}else{
Serial.printf_P(PSTR("Error Reading END_BYTE: %d\n"),data);
}
log_step = 0; // Restart sequence: new packet...
break;
}
page = DataFlash.GetPage();
}
return packet_count;
}
#else // LOGGING_ENABLED

View File

@ -1 +1,28 @@
include ../libraries/AP_Common/Arduino.mk
nologging:
make -f Makefile EXTRAFLAGS="-DLOGGING_ENABLED=DISABLED"
nogps:
make -f Makefile EXTRAFLAGS="-DGPS_PROTOCOL=GPS_PROTOCOL_NONE -DLOGGING_ENABLED=DISABLED"
hil:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
hilsensors:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_SENSORS -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
hilnocli:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
heli:
make -f Makefile EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME"
apm2:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DCLI_SLIDER_ENABLED=DISABLED"
mavlink10:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DMAVLINK10 -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
etags:
cd .. && etags -f ArduCopter/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduCopter libraries)

View File

@ -104,6 +104,7 @@ public:
k_param_optflow_enabled,
k_param_input_voltage,
k_param_low_voltage,
k_param_ch7_option,
//
// 160: Navigation parameters
@ -237,6 +238,7 @@ public:
AP_Int8 radio_tuning;
AP_Int8 frame_orientation;
AP_Float top_bottom_ratio;
AP_Int8 ch7_option;
#if FRAME_CONFIG == HELI_FRAME
@ -341,6 +343,7 @@ public:
radio_tuning (0, k_param_radio_tuning, PSTR("TUNE")),
frame_orientation (FRAME_ORIENTATION, k_param_frame_orientation, PSTR("FRAME")),
top_bottom_ratio (TOP_BOTTOM_RATIO, k_param_top_bottom_ratio, PSTR("TB_RATIO")),
ch7_option (CH7_SAVE_WP, k_param_ch7_option, PSTR("CH7_OPT")),
#if FRAME_CONFIG == HELI_FRAME
heli_servo_1 (k_param_heli_servo_1, PSTR("HS1_")),

View File

@ -34,6 +34,26 @@
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// APM HARDWARE
//
#ifndef CONFIG_APM_HARDWARE
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
#endif
//////////////////////////////////////////////////////////////////////////////
// APM2 HARDWARE DEFAULTS
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
#endif
//////////////////////////////////////////////////////////////////////////////
// FRAME_CONFIG
@ -45,6 +65,30 @@
# define FRAME_ORIENTATION PLUS_FRAME
#endif
//////////////////////////////////////////////////////////////////////////////
// IMU Selection
//
#ifndef CONFIG_IMU_TYPE
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
#endif
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
# ifndef CONFIG_MPU6000_CHIP_SELECT_PIN
# define CONFIG_MPU6000_CHIP_SELECT_PIN 53
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// ADC Enable - used to eliminate for systems which don't have ADC.
//
#ifndef CONFIG_ADC
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
# define CONFIG_ADC ENABLED
# else
# define CONFIG_ADC DISABLED
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// PWM control
@ -53,6 +97,40 @@
# define INSTANT_PWM DISABLED
#endif
// LED and IO Pins
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
# define A_LED_PIN 37
# define B_LED_PIN 36
# define C_LED_PIN 35
# define LED_ON HIGH
# define LED_OFF LOW
# define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED
# define USB_MUX_PIN 23
#endif
//////////////////////////////////////////////////////////////////////////////
// Pushbutton & Relay
//
#ifndef CONFIG_PUSHBUTTON
# define CONFIG_PUSHBUTTON ENABLED
#endif
#ifndef CONFIG_RELAY
# define CONFIG_RELAY ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Sonar
@ -62,10 +140,52 @@
# define SONAR_PORT AP_RANGEFINDER_PITOT_TUBE
#endif
#ifndef CONFIG_SONAR_SOURCE
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ADC
#endif
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC && CONFIG_ADC == DISABLED
# warning Cannot use ADC for CONFIG_SONAR_SOURCE, becaude CONFIG_ADC is DISABLED
# warning Defaulting CONFIG_SONAR_SOURCE to ANALOG_PIN
# undef CONFIG_SONAR_SOURCE
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
#endif
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
# ifndef CONFIG_SONAR_SOURCE_ADC_CHANNEL
# define CONFIG_SONAR_SOURCE_ADC_CHANNEL 7
# endif
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
# ifndef CONFIG_SONAR_SOURCE_ANALOG_PIN
# define CONFIG_SONAR_SOURCE_ANALOG_PIN AN4
# endif
#else
# warning Invalid value for CONFIG_SONAR_SOURCE, disabling sonar
# undef SONAR_ENABLED
# define SONAR_ENABLED DISABLED
#endif
#ifndef SONAR_TYPE
# define SONAR_TYPE MAX_SONAR_XL
#endif
// It seems that MAX_SONAR_XL depends on an ADC. For systems without an
// ADC, we need to disable the sonar
#if SONAR_TYPE == MAX_SONAR_XL
# if CONFIG_ADC == DISABLED
# if defined(CONFIG_SONAR)
# warning "MAX_SONAR_XL requires a valid ADC. This system does not have an ADC enabled."
# undef CONFIG_SONAR
# endif
# define CONFIG_SONAR DISABLED
# endif
#endif
#ifndef CONFIG_SONAR
# define CONFIG_SONAR ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Acrobatics
//
@ -675,10 +795,6 @@
# define CUT_MOTORS 1 // do we cut the motors with no throttle?
#endif
#ifndef BROKEN_SLIDER
# define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
#endif
#ifndef MOTOR_LEDS
# define MOTOR_LEDS 1 // 0 = off, 1 = on
#endif

View File

@ -52,24 +52,8 @@ static void read_trim_switch()
}
#elif CH7_OPTION == CH7_SIMPLE_MODE
do_simple = (g.rc_7.control_in > 800);
//Serial.println(g.rc_7.control_in, DEC);
#elif CH7_OPTION == CH7_RTL
static bool ch7_rtl_flag = false;
if (ch7_rtl_flag == false && g.rc_7.control_in > 800){
ch7_rtl_flag = true;
set_mode(RTL);
}
if (ch7_rtl_flag == true && g.rc_7.control_in < 800){
ch7_rtl_flag = false;
if (control_mode == RTL || control_mode == LOITER){
reset_control_switch();
}
}
#elif CH7_OPTION == CH7_SET_HOVER
// switch is engaged
if (g.rc_7.control_in > 800){
@ -88,12 +72,43 @@ static void read_trim_switch()
}
}
#elif CH7_OPTION == CH7_SAVE_WP
#elif CH7_OPTION == CH7_ADC_FILTER
if (g.rc_7.control_in > 800){
adc.filter_result = true;
}else{
adc.filter_result = false;
}
#elif CH7_OPTION == CH7_AUTO_TRIM
if (g.rc_7.control_in > 800){
auto_level_counter = 10;
}
#else
// this is the normal operation set by the mission planner
if(g.ch7_option == CH7_SIMPLE_MODE){
do_simple = (g.rc_7.control_in > 800);
}else if (g.ch7_option == CH7_RTL){
if (trim_flag == false && g.rc_7.control_in > 800){
trim_flag = true;
set_mode(RTL);
}
if (trim_flag == true && g.rc_7.control_in < 800){
trim_flag = false;
if (control_mode == RTL || control_mode == LOITER){
reset_control_switch();
}
}
}else if (g.ch7_option == CH7_SAVE_WP){
if (g.rc_7.control_in > 800){ // switch is engaged
trim_flag = true;
}else{ // switch is disengaged
if(trim_flag){
trim_flag = false;
// increment index
@ -113,18 +128,7 @@ static void read_trim_switch()
g.command_total.set_and_save(CH7_wp_index + 1);
}
}
#elif CH7_OPTION == CH7_ADC_FILTER
if (g.rc_7.control_in > 800){
adc.filter_result = true;
}else{
adc.filter_result = false;
}
#elif CH7_OPTION == CH7_AUTO_TRIM
if (g.rc_7.control_in > 800){
auto_level_counter = 10;
}
}
#endif
}

View File

@ -29,6 +29,9 @@
#define SONAR 0
#define BARO 1
#define SONAR_SOURCE_ADC 1
#define SONAR_SOURCE_ANALOG_PIN 2
// CH 7 control
#define CH7_DO_NOTHING 0
#define CH7_SET_HOVER 1
@ -330,14 +333,6 @@ enum gcs_severity {
// sonar
//#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters
// Hardware Parameters
#define SLIDE_SWITCH_PIN 40
#define PUSHBUTTON_PIN 41
#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C
#define B_LED_PIN 36
#define C_LED_PIN 35
// RADIANS
#define RADX100 0.000174533
@ -353,4 +348,12 @@ enum gcs_severity {
// mark a function as not to be inlined
#define NOINLINE __attribute__((noinline))
// IMU selection
#define CONFIG_IMU_OILPAN 1
#define CONFIG_IMU_MPU6000 2
// APM Hardware selection
#define APM_HARDWARE_APM1 1
#define APM_HARDWARE_APM2 2
#endif // _DEFINES_H

View File

@ -16,8 +16,13 @@ static void failsafe_on_event()
// 2 = Stay in AUTO and ignore failsafe
default:
// not ready to enable yet w/o more testing
//set_mode(RTL);
if(home_is_set == true){
if ((get_distance(&current_loc, &home) > 15) && (current_loc.alt > 400)){
set_mode(RTL);
// override safety
motor_auto_armed = true;
}
}
break;
}
}

View File

@ -207,9 +207,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 8000; // 250 hz output CH 1, 2, 9
ICR1 = 8000; // 250 hz output CH 3, 4, 10
ICR3 = 40000; // 50 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 );
#endif
}

View File

@ -19,23 +19,23 @@ static void update_GPS_light(void)
switch (g_gps->status()){
case(2):
digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix.
digitalWrite(C_LED_PIN, LED_ON); //Turn LED C on when gps has valid fix.
break;
case(1):
if (g_gps->valid_read == true){
GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock
if (GPS_light){
digitalWrite(C_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
}else{
digitalWrite(C_LED_PIN, HIGH);
digitalWrite(C_LED_PIN, LED_ON);
}
g_gps->valid_read = false;
}
break;
default:
digitalWrite(C_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
break;
}
}
@ -47,14 +47,14 @@ static void update_motor_light(void)
// blink
if(motor_light){
digitalWrite(A_LED_PIN, HIGH);
digitalWrite(A_LED_PIN, LED_ON);
}else{
digitalWrite(A_LED_PIN, LOW);
digitalWrite(A_LED_PIN, LED_OFF);
}
}else{
if(!motor_light){
motor_light = true;
digitalWrite(A_LED_PIN, HIGH);
digitalWrite(A_LED_PIN, LED_ON);
}
}
}
@ -69,26 +69,26 @@ static void dancing_light()
switch(step)
{
case 0:
digitalWrite(C_LED_PIN, LOW);
digitalWrite(A_LED_PIN, HIGH);
digitalWrite(C_LED_PIN, LED_OFF);
digitalWrite(A_LED_PIN, LED_ON);
break;
case 1:
digitalWrite(A_LED_PIN, LOW);
digitalWrite(B_LED_PIN, HIGH);
digitalWrite(A_LED_PIN, LED_OFF);
digitalWrite(B_LED_PIN, LED_ON);
break;
case 2:
digitalWrite(B_LED_PIN, LOW);
digitalWrite(C_LED_PIN, HIGH);
digitalWrite(B_LED_PIN, LED_OFF);
digitalWrite(C_LED_PIN, LED_ON);
break;
}
}
static void clear_leds()
{
digitalWrite(A_LED_PIN, LOW);
digitalWrite(B_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LOW);
digitalWrite(A_LED_PIN, LED_OFF);
digitalWrite(B_LED_PIN, LED_OFF);
digitalWrite(C_LED_PIN, LED_OFF);
motor_light = false;
led_mode = NORMAL_LEDS;
}

View File

@ -66,7 +66,7 @@ static void arm_motors()
static void init_arm_motors()
{
//Serial.printf("\nARM\n");
#if HIL_MODE != HIL_MODE_DISABLED
#if HIL_MODE != HIL_MODE_DISABLED || defined(DESKTOP_BUILD)
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
#endif
@ -107,7 +107,7 @@ static void init_arm_motors()
static void init_disarm_motors()
{
//Serial.printf("\nDISARM\n");
#if HIL_MODE != HIL_MODE_DISABLED
#if HIL_MODE != HIL_MODE_DISABLED || defined(DESKTOP_BUILD)
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
#endif

View File

@ -5,9 +5,8 @@
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 400 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
| MSK_CH_7 | MSK_CH_8 );
#endif
}

View File

@ -5,9 +5,8 @@
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 400 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
| MSK_CH_7 | MSK_CH_8 | MSK_CH_10 | MSK_CH_11 );
#endif
}

View File

@ -5,9 +5,8 @@
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 400 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
| MSK_CH_7 | MSK_CH_8 | MSK_CH_10 | MSK_CH_11 );
#endif
}

View File

@ -5,9 +5,7 @@
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 40000; // 50 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 );
#endif
}

View File

@ -4,9 +4,7 @@
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 40000; // 50 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_4 );
#endif
}

View File

@ -7,9 +7,8 @@
static void init_motors_out()
{
#if INSTANT_PWM == 0
ICR5 = 5000; // 400 hz output CH 1, 2, 9
ICR1 = 5000; // 400 hz output CH 3, 4, 10
ICR3 = 5000; // 400 hz output CH 7, 8, 11
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
| MSK_CH_7 | MSK_CH_8 );
#endif
}

View File

@ -35,6 +35,8 @@ planner_gcs(uint8_t argc, const Menu::arg *argv)
fast_loopTimer = millis();
gcs_update();
read_radio();
gcs_data_stream_send(45, 1000);

View File

@ -54,17 +54,9 @@ static void init_rc_in()
static void init_rc_out()
{
APM_RC.Init(); // APM Radio initialization
APM_RC.Init( &isr_registry ); // APM Radio initialization
init_motors_out();
// fix for crazy output
OCR1B = 0xFFFF; // PB6, OUT3
OCR1C = 0xFFFF; // PB7, OUT4
OCR5B = 0xFFFF; // PL4, OUT1
OCR5C = 0xFFFF; // PL5, OUT2
OCR4B = 0xFFFF; // PH4, OUT6
OCR4C = 0xFFFF; // PH5, OUT5
// this is the camera pitch5 and roll6
APM_RC.OutputCh(CH_5, 1500);
APM_RC.OutputCh(CH_6, 1500);
@ -147,7 +139,7 @@ static void read_radio()
g.rc_3.control_in = min(g.rc_3.control_in, 800);
#endif
//throttle_failsafe(g.rc_3.radio_in);
throttle_failsafe(g.rc_3.radio_in);
}
}
@ -166,8 +158,8 @@ static void throttle_failsafe(uint16_t pwm)
SendDebug("MSG FS ON ");
SendDebugln(pwm, DEC);
}else if(failsafeCounter == 10) {
ch3_failsafe = true;
//set_failsafe(true);
//ch3_failsafe = true;
set_failsafe(true);
//failsafeCounter = 10;
}else if (failsafeCounter > 10){
failsafeCounter = 11;
@ -184,8 +176,8 @@ static void throttle_failsafe(uint16_t pwm)
SendDebug("MSG FS OFF ");
SendDebugln(pwm, DEC);
}else if(failsafeCounter == 0) {
ch3_failsafe = false;
//set_failsafe(false);
//ch3_failsafe = false;
set_failsafe(false);
//failsafeCounter = -1;
}else if (failsafeCounter <0){
failsafeCounter = -1;

View File

@ -55,6 +55,24 @@ static void run_cli(void)
static void init_ardupilot()
{
#if USB_MUX_PIN > 0
// on the APM2 board we have a mux thet switches UART0 between
// USB and the board header. If the right ArduPPM firmware is
// installed we can detect if USB is connected using the
// USB_MUX_PIN
pinMode(USB_MUX_PIN, INPUT);
usb_connected = !digitalRead(USB_MUX_PIN);
if (!usb_connected) {
// USB is not connected, this means UART0 may be a Xbee, with
// its darned bricking problem. We can't write to it for at
// least one second after powering up. Simplest solution for
// now is to delay for 1 second. Something more elegant may be
// added later
delay(1000);
}
#endif
// Console serial port
//
// The console port buffers are defined to be sufficiently large to support
@ -85,6 +103,10 @@ static void init_ardupilot()
"\n\nFree RAM: %u\n"),
memcheck_available_memory());
//
// Initialize the isr_registry.
//
isr_registry.init();
//
// Check the EEPROM format version before loading any parameters from EEPROM.
@ -92,13 +114,24 @@ static void init_ardupilot()
report_version();
// setup IO pins
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
pinMode(A_LED_PIN, OUTPUT); // GPS status LED
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
pinMode(PUSHBUTTON_PIN, INPUT); // unused
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
digitalWrite(A_LED_PIN, LED_OFF);
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
digitalWrite(B_LED_PIN, LED_OFF);
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
digitalWrite(C_LED_PIN, LED_OFF);
#if SLIDE_SWITCH_PIN > 0
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
#endif
#if CONFIG_PUSHBUTTON == ENABLED
pinMode(PUSHBUTTON_PIN, INPUT); // unused
#endif
#if CONFIG_RELAY == ENABLED
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
#endif
// XXX set Analog out 14 to output
// 76543210
//DDRK |= B01010000;
@ -131,6 +164,9 @@ static void init_ardupilot()
delay(100); // wait for serial send
AP_Var::erase_all();
// clear logs
erase_logs(NULL, NULL);
// save the new format version
g.format_version.set_and_save(Parameters::k_format_version);
@ -141,13 +177,13 @@ static void init_ardupilot()
while (true) {
delay(1000);
if(motor_light){
digitalWrite(A_LED_PIN, HIGH);
digitalWrite(B_LED_PIN, HIGH);
digitalWrite(C_LED_PIN, HIGH);
digitalWrite(A_LED_PIN, LED_ON);
digitalWrite(B_LED_PIN, LED_ON);
digitalWrite(C_LED_PIN, LED_ON);
}else{
digitalWrite(A_LED_PIN, LOW);
digitalWrite(B_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LOW);
digitalWrite(A_LED_PIN, LED_OFF);
digitalWrite(B_LED_PIN, LED_OFF);
digitalWrite(C_LED_PIN, LED_OFF);
}
motor_light = !motor_light;
}
@ -160,15 +196,20 @@ static void init_ardupilot()
AP_Var::load_all();
}
// Telemetry port.
//
// Not used if telemetry is going to the console.
//
// XXX for unidirectional protocols, we could (should) minimize
// the receive buffer, and the transmit buffer could also be
// shrunk for protocols that don't send large messages.
//
Serial3.begin(map_baudrate(g.serial3_baud,SERIAL3_BAUD), 128, 128);
// init the GCS
gcs0.init(&Serial);
#if USB_MUX_PIN > 0
if (!usb_connected) {
// we are not connected via USB, re-init UART0 with right
// baud rate
Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
}
#else
// we have a 2nd serial port for telemetry
Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
gcs3.init(&Serial3);
#endif
#ifdef RADIO_OVERRIDE_DEFAULTS
{
@ -182,28 +223,34 @@ static void init_ardupilot()
heli_init_swash(); // heli initialisation
#endif
RC_Channel::set_apm_rc(&APM_RC);
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up the timer libs
init_camera();
#if HIL_MODE != HIL_MODE_ATTITUDE
timer_scheduler.init( &isr_registry );
#if HIL_MODE != HIL_MODE_ATTITUDE
#if CONFIG_ADC == ENABLED
// begin filtering the ADC Gyros
adc.filter_result = true;
adc.Init(&timer_scheduler); // APM ADC library initialization
#endif // CONFIG_ADC
adc.Init(); // APM ADC library initialization
barometer.Init(); // APM Abs Pressure sensor initialization
#endif
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
barometer.Init(1, true);
#else
barometer.Init(1, false);
#endif // CONFIG_APM_HARDWARE
#endif // HIL_MODE
// Do GPS init
g_gps = &g_gps_driver;
g_gps->init(); // GPS Initialization
g_gps->callback = mavlink_delay;
// init the GCS
gcs0.init(&Serial);
gcs3.init(&Serial3);
if(g.compass_enabled)
init_compass();
@ -231,7 +278,7 @@ static void init_ardupilot()
// menu; they must reset in order to fly.
//
if (check_startup_for_CLI()) {
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
digitalWrite(A_LED_PIN, LED_ON); // turn on setup-mode LED
Serial.printf_P(PSTR("\nCLI:\n\n"));
run_cli();
}
@ -305,11 +352,13 @@ static void init_ardupilot()
startup_ground();
#if LOGGING_ENABLED == ENABLED
Log_Write_Startup();
Log_Write_Data(10, g.pi_stabilize_roll.kP());
Log_Write_Data(11, g.pi_stabilize_pitch.kP());
Log_Write_Data(12, g.pi_rate_roll.kP());
Log_Write_Data(13, g.pi_rate_pitch.kP());
#endif
SendDebug("\nReady to FLY ");
}
@ -324,7 +373,7 @@ static void startup_ground(void)
#if HIL_MODE != HIL_MODE_ATTITUDE
// Warm up and read Gyro offsets
// -----------------------------
imu.init_gyro(mavlink_delay);
imu.init(IMU::COLD_START, mavlink_delay, &timer_scheduler);
#if CLI_ENABLED == ENABLED
report_imu();
#endif
@ -543,36 +592,12 @@ init_throttle_cruise()
}
}
#if CLI_ENABLED == ENABLED
#if BROKEN_SLIDER == 1
static boolean
check_startup_for_CLI()
{
//return true;
if((g.rc_4.radio_max) < 1600){
// CLI mode
return true;
}else if(abs(g.rc_4.control_in) > 3000){
// CLI mode
return true;
}else{
// startup to fly
return false;
}
}
#else
#if CLI_SLIDER_ENABLED == ENABLED && CLI_ENABLED == ENABLED
static boolean
check_startup_for_CLI()
{
return (digitalRead(SLIDE_SWITCH_PIN) == 0);
}
#endif // BROKEN_SLIDER
#endif // CLI_ENABLED
/*
@ -591,3 +616,21 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
//Serial.println_P(PSTR("Invalid SERIAL3_BAUD"));
return default_baud;
}
#if USB_MUX_PIN > 0
static void check_usb_mux(void)
{
bool usb_check = !digitalRead(USB_MUX_PIN);
if (usb_check == usb_connected) {
return;
}
// the user has switched to/from the telemetry port
usb_connected = usb_check;
if (usb_connected) {
Serial.begin(SERIAL0_BAUD, 128, 128);
} else {
Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
}
}
#endif

View File

@ -11,7 +11,13 @@ static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
//static int8_t test_tri(uint8_t argc, const Menu::arg *argv);
//static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
#if HIL_MODE != HIL_MODE_ATTITUDE
static int8_t test_ins(uint8_t argc, const Menu::arg *argv);
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
static int8_t test_dcm_eulers(uint8_t argc, const Menu::arg *argv);
#endif // HIL_MODE
//static int8_t test_dcm(uint8_t argc, const Menu::arg *argv);
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
@ -59,11 +65,14 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
// {"failsafe", test_failsafe},
// {"stabilize", test_stabilize},
{"gps", test_gps},
#if HIL_MODE != HIL_MODE_ATTITUDE
#if HIL_MODE != HIL_MODE_ATTITUDE && CONFIG_ADC == ENABLED
// {"adc", test_adc},
#endif
#if HIL_MODE != HIL_MODE_ATTITUDE
{"ins", test_ins},
{"imu", test_imu},
//{"dcm", test_dcm},
{"dcm", test_dcm_eulers},
#endif
//{"omega", test_omega},
{"battery", test_battery},
{"tune", test_tuning},
@ -75,7 +84,9 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
#if HIL_MODE != HIL_MODE_ATTITUDE
{"altitude", test_baro},
#endif
#if CONFIG_SONAR == ENABLED
{"sonar", test_sonar},
#endif
//{"compass", test_mag},
#ifdef OPTFLOW_ENABLED
{"optflow", test_optflow},
@ -391,7 +402,8 @@ static int8_t
}
*/
/*#if HIL_MODE != HIL_MODE_ATTITUDE
/*#if HIL_MODE != HIL_MODE_ATTITUDE && CONFIG_ADC == ENABLED
static int8_t
//test_adc(uint8_t argc, const Menu::arg *argv)
{
@ -399,6 +411,10 @@ static int8_t
Serial.printf_P(PSTR("ADC\n"));
delay(1000);
adc.Init(&timer_scheduler);
delay(50);
while(1){
for(int i = 0; i < 9; i++){
Serial.printf_P(PSTR("%u,"),adc.Ch(i));
@ -413,14 +429,98 @@ static int8_t
#endif
*/
#if HIL_MODE != HIL_MODE_ATTITUDE
static int8_t
test_ins(uint8_t argc, const Menu::arg *argv)
{
float gyro[3], accel[3], temp;
print_hit_enter();
Serial.printf_P(PSTR("InertialSensor\n"));
delay(1000);
ins.init(&timer_scheduler);
delay(50);
while(1){
ins.update();
ins.get_gyros(gyro);
ins.get_accels(accel);
temp = ins.temperature();
Serial.printf_P(PSTR("g"));
for (int i = 0; i < 3; i++) {
Serial.printf_P(PSTR(" %7.4f"), gyro[i]);
}
Serial.printf_P(PSTR(" a"));
for (int i = 0; i < 3; i++) {
Serial.printf_P(PSTR(" %7.4f"),accel[i]);
}
Serial.printf_P(PSTR(" t %7.4f \n"), temp);
delay(40);
if(Serial.available() > 0){
return (0);
}
}
}
#endif // HIL_MODE
#if HIL_MODE != HIL_MODE_ATTITUDE
/*
test the IMU interface
*/
static int8_t
test_imu(uint8_t argc, const Menu::arg *argv)
{
Vector3f gyro;
Vector3f accel;
imu.init(IMU::WARM_START, delay, &timer_scheduler);
report_imu();
imu.init_gyro();
report_imu();
print_hit_enter();
delay(1000);
while(1){
delay(40);
imu.update();
gyro = imu.get_gyro();
accel = imu.get_accel();
Serial.printf_P(PSTR("g %8.4f %8.4f %8.4f"), gyro.x, gyro.y, gyro.z);
Serial.printf_P(PSTR(" a %8.4f %8.4f %8.4f\n"), accel.x, accel.y, accel.z);
if(Serial.available() > 0){
return (0);
}
}
return 0;
}
#endif // HIL_MODE
#if HIL_MODE != HIL_MODE_ATTITUDE
/*
test the DCM code, printing Euler angles
*/
static int8_t
test_dcm_eulers(uint8_t argc, const Menu::arg *argv)
{
//Serial.printf_P(PSTR("Calibrating."));
//dcm.kp_yaw(0.02);
//dcm.ki_yaw(0);
imu.init(IMU::WARM_START, delay, &timer_scheduler);
report_imu();
imu.init_gyro();
report_imu();
@ -444,7 +544,6 @@ test_imu(uint8_t argc, const Menu::arg *argv)
//Vector3f accel_filt = imu.get_accel_filtered();
//accels_rot = dcm.get_dcm_matrix() * accel_filt;
medium_loopCounter++;
if(medium_loopCounter == 4){
@ -452,57 +551,28 @@ test_imu(uint8_t argc, const Menu::arg *argv)
}
if(medium_loopCounter == 1){
//read_radio();
medium_loopCounter = 0;
//tuning();
//dcm.kp_roll_pitch((float)g.rc_6.control_in / 2000.0);
/*
Serial.printf_P(PSTR("r: %ld\tp: %ld\t y: %ld, kp:%1.4f, kp:%1.4f \n"),
dcm.roll_sensor,
dcm.pitch_sensor,
dcm.yaw_sensor,
dcm.kp_roll_pitch(),
(float)g.rc_6.control_in / 2000.0);
*/
Serial.printf_P(PSTR("%ld, %ld, %ld, | %ld, %ld, %ld\n"),
dcm.roll_sensor,
dcm.pitch_sensor,
dcm.yaw_sensor,
(long)(degrees(omega.x) * 100.0),
(long)(degrees(omega.y) * 100.0),
(long)(degrees(omega.z) * 100.0));
Serial.printf_P(PSTR("dcm: %6.1f, %6.1f, %6.1f omega: %6.1f, %6.1f, %6.1f\n"),
dcm.roll_sensor/100.0,
dcm.pitch_sensor/100.0,
dcm.yaw_sensor/100.0,
degrees(omega.x),
degrees(omega.y),
degrees(omega.z));
if(g.compass_enabled){
compass.read(); // Read magnetometer
compass.calculate(dcm.get_dcm_matrix());
}
}
// We are using the IMU
// ---------------------
/*
Serial.printf_P(PSTR("A: %4.4f, %4.4f, %4.4f\t"
"G: %4.4f, %4.4f, %4.4f\t"),
accels.x, accels.y, accels.z,
gyros.x, gyros.y, gyros.z);
*/
/*
Serial.printf_P(PSTR("cp: %1.2f, sp: %1.2f, cr: %1.2f, sr: %1.2f, cy: %1.2f, sy: %1.2f,\n"),
cos_pitch_x,
sin_pitch_y,
cos_roll_x,
sin_roll_y,
cos_yaw_x, // x
sin_yaw_y); // y
//*/
//Log_Write_Raw();
fast_loopTimer = millis();
}
if(Serial.available() > 0){
return (0);
}
}
}
#endif // HIL_MODE
static int8_t
test_gps(uint8_t argc, const Menu::arg *argv)
@ -763,14 +833,14 @@ test_wp(uint8_t argc, const Menu::arg *argv)
delay(1000);
while(1){
if (Serial3.available()){
digitalWrite(B_LED_PIN, HIGH); // Blink Yellow LED if we are sending data to GPS
digitalWrite(B_LED_PIN, LED_ON); // Blink Yellow LED if we are sending data to GPS
Serial1.write(Serial3.read());
digitalWrite(B_LED_PIN, LOW);
digitalWrite(B_LED_PIN, LED_OFF);
}
if (Serial1.available()){
digitalWrite(C_LED_PIN, HIGH); // Blink Red LED if we are receiving data from GPS
digitalWrite(C_LED_PIN, LED_ON); // Blink Red LED if we are receiving data from GPS
Serial3.write(Serial1.read());
digitalWrite(C_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
}
if(Serial.available() > 0){
return (0);
@ -898,6 +968,7 @@ static int8_t
/*
test the sonar
*/
#if CONFIG_SONAR == ENABLED
static int8_t
test_sonar(uint8_t argc, const Menu::arg *argv)
{
@ -920,6 +991,7 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
return (0);
}
#endif
#ifdef OPTFLOW_ENABLED
static int8_t

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduPlane V2.26"
#define THISFIRMWARE "ArduPlane V2.27 Alpha"
/*
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short
Thanks to: Chris Anderson, HappyKillMore, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi
@ -26,15 +26,19 @@ version 2.1 of the License, or (at your option) any later version.
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <AP_GPS.h> // ArduPilot GPS library
#include <Wire.h> // Arduino I2C lib
#include <SPI.h> // Arduino SPI lib
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
#include <AP_AnalogSource.h>// ArduPilot Mega polymorphic analog getter
#include <AP_PeriodicProcess.h> // ArduPilot Mega TimerProcess and TimerAperiodicProcess
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
#include <AP_IMU.h> // ArduPilot Mega IMU Library
#include <AP_DCM.h> // ArduPilot Mega DCM Library
#include <PID.h> // PID library
@ -66,6 +70,31 @@ FastSerialPort0(Serial); // FTDI/console
FastSerialPort1(Serial1); // GPS port
FastSerialPort3(Serial3); // Telemetry port
////////////////////////////////////////////////////////////////////////////////
// ISR Registry
////////////////////////////////////////////////////////////////////////////////
Arduino_Mega_ISR_Registry isr_registry;
////////////////////////////////////////////////////////////////////////////////
// APM_RC_Class Instance
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
APM_RC_APM2 APM_RC;
#else
APM_RC_APM1 APM_RC;
#endif
////////////////////////////////////////////////////////////////////////////////
// Dataflash
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
DataFlash_APM2 DataFlash;
#else
DataFlash_APM1 DataFlash;
#endif
////////////////////////////////////////////////////////////////////////////////
// Parameters
////////////////////////////////////////////////////////////////////////////////
@ -103,8 +132,14 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
// real sensors
static AP_ADC_ADS7844 adc;
#ifdef DESKTOP_BUILD
APM_BMP085_HIL_Class barometer;
AP_Compass_HIL compass;
#else
static APM_BMP085_Class barometer;
static AP_Compass_HMC5843 compass(Parameters::k_param_compass);
#endif
// real GPS selection
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
@ -132,12 +167,25 @@ AP_GPS_None g_gps_driver(NULL);
#error Unrecognised GPS_PROTOCOL setting.
#endif // GPS PROTOCOL
# if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN );
# else
AP_InertialSensor_Oilpan ins( &adc );
#endif // CONFIG_IMU_TYPE
AP_IMU_INS imu( &ins, Parameters::k_param_IMU_calibration );
AP_DCM dcm(&imu, g_gps);
AP_TimerProcess timer_scheduler;
#elif HIL_MODE == HIL_MODE_SENSORS
// sensor emulators
AP_ADC_HIL adc;
APM_BMP085_HIL_Class barometer;
AP_Compass_HIL compass;
AP_GPS_HIL g_gps_driver(NULL);
AP_InertialSensor_Oilpan ins( &adc );
AP_IMU_Shim imu;
AP_DCM dcm(&imu, g_gps);
AP_TimerProcess timer_scheduler;
#elif HIL_MODE == HIL_MODE_ATTITUDE
AP_ADC_HIL adc;
@ -150,17 +198,6 @@ AP_IMU_Shim imu; // never used
#error Unrecognised HIL_MODE setting.
#endif // HIL MODE
#if HIL_MODE != HIL_MODE_ATTITUDE
#if HIL_MODE != HIL_MODE_SENSORS
// Normal
AP_IMU_Oilpan imu(&adc, Parameters::k_param_IMU_calibration);
#else
// hil imu
AP_IMU_Shim imu;
#endif
// normal dcm
AP_DCM dcm(&imu, g_gps);
#endif
////////////////////////////////////////////////////////////////////////////////
// GCS selection
@ -170,17 +207,24 @@ GCS_MAVLINK gcs0(Parameters::k_param_streamrates_port0);
GCS_MAVLINK gcs3(Parameters::k_param_streamrates_port3);
////////////////////////////////////////////////////////////////////////////////
// SONAR selection
// PITOT selection
////////////////////////////////////////////////////////////////////////////////
//
ModeFilter sonar_mode_filter;
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
AP_AnalogSource_ADC pitot_analog_source( &adc,
CONFIG_PITOT_SOURCE_ADC_CHANNEL, 0.25);
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN);
#endif
#if SONAR_TYPE == MAX_SONAR_XL
AP_RangeFinder_MaxsonarXL sonar(&adc, &sonar_mode_filter);//(SONAR_PORT, &adc);
AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter);
#elif SONAR_TYPE == MAX_SONAR_LV
// XXX honestly I think these output the same values
// If someone knows, can they confirm it?
AP_RangeFinder_MaxsonarXL sonar(&adc, &sonar_mode_filter);//(SONAR_PORT, &adc);
AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter);
#endif
////////////////////////////////////////////////////////////////////////////////
@ -191,6 +235,10 @@ byte control_mode = INITIALISING;
byte oldSwitchPosition; // for remembering the control mode switch
bool inverted_flight = false;
#if USB_MUX_PIN > 0
static bool usb_connected;
#endif
static const char *comma = ",";
static const char* flight_mode_strings[] = {
@ -694,6 +742,11 @@ static void slow_loop()
mavlink_system.sysid = g.sysid_this_mav; // This is just an ugly hack to keep mavlink_system.sysid sync'd with our parameter
gcs_data_stream_send(3,5);
#if USB_MUX_PIN > 0
check_usb_mux();
#endif
break;
}
}

View File

@ -40,7 +40,10 @@ public:
///
/// @param port The stream over which messages are exchanged.
///
void init(FastSerial *port) { _port = port; }
void init(FastSerial *port) {
_port = port;
initialised = true;
}
/// Update GCS state.
///
@ -83,6 +86,9 @@ public:
// send streams which match frequency range
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
// set to true if this GCS link is active
bool initialised;
protected:
/// The stream we are communicating over
FastSerial *_port;

View File

@ -592,7 +592,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
if (chan == MAVLINK_COMM_0) {
gcs0.queued_param_send();
} else {
} else if (gcs3.initialised) {
gcs3.queued_param_send();
}
break;
@ -601,7 +601,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
CHECK_PAYLOAD_SIZE(WAYPOINT_REQUEST);
if (chan == MAVLINK_COMM_0) {
gcs0.queued_waypoint_send();
} else {
} else if (gcs3.initialised) {
gcs3.queued_waypoint_send();
}
break;
@ -2022,6 +2022,9 @@ static void mavlink_delay(unsigned long t)
gcs_update();
}
delay(1);
#if USB_MUX_PIN > 0
check_usb_mux();
#endif
} while (millis() - tstart < t);
in_mavlink_delay = false;
@ -2033,7 +2036,9 @@ static void mavlink_delay(unsigned long t)
static void gcs_send_message(enum ap_message id)
{
gcs0.send_message(id);
gcs3.send_message(id);
if (gcs3.initialised) {
gcs3.send_message(id);
}
}
/*
@ -2042,7 +2047,9 @@ static void gcs_send_message(enum ap_message id)
static void gcs_data_stream_send(uint16_t freqMin, uint16_t freqMax)
{
gcs0.data_stream_send(freqMin, freqMax);
gcs3.data_stream_send(freqMin, freqMax);
if (gcs3.initialised) {
gcs3.data_stream_send(freqMin, freqMax);
}
}
/*
@ -2051,19 +2058,25 @@ static void gcs_data_stream_send(uint16_t freqMin, uint16_t freqMax)
static void gcs_update(void)
{
gcs0.update();
gcs3.update();
if (gcs3.initialised) {
gcs3.update();
}
}
static void gcs_send_text(gcs_severity severity, const char *str)
{
gcs0.send_text(severity, str);
gcs3.send_text(severity, str);
if (gcs3.initialised) {
gcs3.send_text(severity, str);
}
}
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
{
gcs0.send_text(severity, str);
gcs3.send_text(severity, str);
if (gcs3.initialised) {
gcs3.send_text(severity, str);
}
}
/*

View File

@ -87,9 +87,14 @@ print_log_menu(void)
Serial.printf_P(PSTR("\n%d logs\n"), num_logs);
for(int i=num_logs;i>=1;i--) {
int last_log_start = log_start, last_log_end = log_end;
temp = g.log_last_filenumber-i+1;
get_log_boundaries(temp, log_start, log_end);
Serial.printf_P(PSTR("Log %d, start %d, end %d\n"), temp, log_start, log_end);
if (last_log_start == log_start && last_log_end == log_end) {
// we are printing bogus logs
break;
}
}
Serial.println();
}
@ -99,7 +104,7 @@ print_log_menu(void)
static int8_t
dump_log(uint8_t argc, const Menu::arg *argv)
{
byte dump_log;
int dump_log;
int dump_log_start;
int dump_log_end;
byte last_log_num;
@ -107,9 +112,12 @@ dump_log(uint8_t argc, const Menu::arg *argv)
// check that the requested log number can be read
dump_log = argv[1].i;
last_log_num = g.log_last_filenumber;
if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
if (dump_log == -1) {
Serial.printf_P(PSTR("dumping all\n"));
Log_Read(1, DF_LAST_PAGE);
return(-1);
} else if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
Serial.printf_P(PSTR("bad log number\n"));
Log_Read(0, 4095);
return(-1);
}
@ -127,10 +135,6 @@ dump_log(uint8_t argc, const Menu::arg *argv)
static int8_t
erase_logs(uint8_t argc, const Menu::arg *argv)
{
for(int i = 10 ; i > 0; i--) {
Serial.printf_P(PSTR("ATTENTION - Erasing log in %d seconds. Power off now to save log! \n"), i);
delay(1000);
}
Serial.printf_P(PSTR("\nErasing log...\n"));
DataFlash.SetFileNumber(0xFFFF);
for(int j = 1; j <= DF_LAST_PAGE; j++) {
@ -140,6 +144,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
g.log_last_filenumber.set_and_save(0);
Serial.printf_P(PSTR("\nLog erased.\n"));
DataFlash.FinishWrite();
return 0;
}
@ -245,6 +250,8 @@ static void start_new_log()
static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
{
int num = get_num_logs();
int look;
if(num == 1)
{
DataFlash.StartRead(DF_LAST_PAGE);
@ -258,147 +265,133 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
}
} else {
end_page = find_last_log_page((uint16_t)log_num);
if(log_num==1)
start_page = 1;
else
if(log_num == g.log_last_filenumber - num + 1) {
start_page = find_last_log_page(g.log_last_filenumber) + 1;
if(log_num==1) {
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF) {
start_page = 1;
} else {
start_page = find_last_log_page((uint16_t)(log_num-1)) + 1;
start_page = find_last() + 1;
}
} else {
if(log_num == g.log_last_filenumber - num + 1) {
start_page = find_last() + 1;
} else {
look = log_num-1;
do {
start_page = find_last_log_page(look) + 1;
look--;
} while (start_page <= 0);
}
}
}
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
end_page = find_last_log_page((uint16_t)log_num);
if(end_page <= 0) end_page = start_page;
}
static bool check_wrapped(void)
{
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
return 0;
else
return 1;
}
// This function finds the last page of the last file
// It also cleans up in the situation where a file was initiated, but no pages written
static int find_last(void)
{
int16_t num;
do
{
num = find_last_log_page(g.log_last_filenumber);
if (num == -1) g.log_last_filenumber.set_and_save(g.log_last_filenumber - 1);
} while (num == -1);
return num;
uint16_t look;
uint16_t bottom = 1;
uint16_t top = DF_LAST_PAGE;
uint32_t look_hash;
uint32_t bottom_hash;
uint32_t top_hash;
DataFlash.StartRead(bottom);
bottom_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
while(top-bottom > 1)
{
look = (top+bottom)/2;
DataFlash.StartRead(look);
look_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
if (look_hash >= 0xFFFF0000) look_hash = 0;
if(look_hash < bottom_hash) {
// move down
top = look;
} else {
// move up
bottom = look;
bottom_hash = look_hash;
}
}
DataFlash.StartRead(top);
top_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
if (top_hash >= 0xFFFF0000) top_hash = 0;
if (top_hash > bottom_hash)
{
return top;
} else {
return bottom;
}
}
// This function finds the last page of a particular log file
static int find_last_log_page(uint16_t log_number)
{
uint16_t bottom_page;
uint16_t bottom_page_file;
uint16_t bottom_page_filepage;
uint16_t top_page;
uint16_t top_page_file;
uint16_t top_page_filepage;
uint16_t look_page;
uint16_t look_page_file;
uint16_t look_page_filepage;
uint16_t look;
uint16_t bottom;
uint16_t top;
uint32_t look_hash;
uint32_t check_hash;
bottom_page = 1;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
// First see if the logs are empty. If so we will exit right away.
if(bottom_page_file == 0XFFFF) {
return 0;
}
top_page = DF_LAST_PAGE;
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
top_page_filepage = DataFlash.GetFilePage();
while((top_page - bottom_page) > 1) {
look_page = ((long)top_page + (long)bottom_page) / 2L;
DataFlash.StartRead(look_page);
look_page_file = DataFlash.GetFileNumber();
look_page_filepage = DataFlash.GetFilePage();
// We have a lot of different logic cases dependant on if the log space is overwritten
// and where log breaks might occur relative to binary search points.
// Someone could make work up a logic table and simplify this perhaps, or perhaps
// it is easier to interpret as is.
if (look_page_file == 0xFFFF) {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
} else if (look_page_file == log_number && bottom_page_file == log_number && top_page_file == log_number) {
// This case is typical if a single file fills the log and partially overwrites itself
if (bottom_page_filepage < top_page_filepage) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
}
} else if (look_page_file == log_number && look_page_file ==bottom_page_file) {
if (bottom_page_filepage < look_page_filepage) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
}
} else if (look_page_file == log_number) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else if(look_page_file < log_number && bottom_page_file > look_page_file && bottom_page_file <= log_number) {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
} else if(look_page_file < log_number) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
} else if(look_page_file > log_number && top_page_file < look_page_file && top_page_file >= log_number) {
bottom_page = look_page;
bottom_page_file = look_page_file;
bottom_page_filepage = look_page_filepage;
if(check_wrapped())
{
DataFlash.StartRead(1);
bottom = DataFlash.GetFileNumber();
if (bottom > log_number)
{
bottom = find_last();
top = DF_LAST_PAGE;
} else {
top_page = look_page;
top_page_file = look_page_file;
top_page_filepage = look_page_filepage;
bottom = 1;
top = find_last();
}
// End while
}
if (bottom_page_file == log_number && top_page_file == log_number) {
if( bottom_page_filepage < top_page_filepage)
return top_page;
else
return bottom_page;
} else if (bottom_page_file == log_number) {
return bottom_page;
} else if (top_page_file == log_number) {
return top_page;
} else {
return -1;
bottom = 1;
top = find_last();
}
check_hash = (long)log_number<<16 | 0xFFFF;
while(top-bottom > 1)
{
look = (top+bottom)/2;
DataFlash.StartRead(look);
look_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
if (look_hash >= 0xFFFF0000) look_hash = 0;
if(look_hash > check_hash) {
// move down
top = look;
} else {
// move up
bottom = look;
}
}
DataFlash.StartRead(top);
if (DataFlash.GetFileNumber() == log_number) return top;
DataFlash.StartRead(bottom);
if (DataFlash.GetFileNumber() == log_number) return bottom;
return -1;
}
// Write an attitude packet. Total length : 10 bytes

View File

@ -1 +1,28 @@
include ../libraries/AP_Common/Arduino.mk
nologging:
make -f Makefile EXTRAFLAGS="-DLOGGING_ENABLED=DISABLED"
nogps:
make -f Makefile EXTRAFLAGS="-DGPS_PROTOCOL=GPS_PROTOCOL_NONE -DLOGGING_ENABLED=DISABLED"
hil:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
hilsensors:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_SENSORS -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
hilnocli:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
heli:
make -f Makefile EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME"
apm2:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2"
mavlink10:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DMAVLINK10 -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
etags:
cd .. && etags -f ArduPlane/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduPlane libraries)

View File

@ -42,6 +42,49 @@
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// APM HARDWARE
//
#ifndef CONFIG_APM_HARDWARE
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
#endif
//////////////////////////////////////////////////////////////////////////////
// APM2 HARDWARE DEFAULTS
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
#endif
// LED and IO Pins
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
# define A_LED_PIN 37
# define B_LED_PIN 36
# define C_LED_PIN 35
# define LED_ON HIGH
# define LED_OFF LOW
# define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED
# define USB_MUX_PIN 23
#endif
//////////////////////////////////////////////////////////////////////////////
// AIRSPEED_SENSOR
// AIRSPEED_RATIO
@ -55,21 +98,63 @@
#endif
//////////////////////////////////////////////////////////////////////////////
// Sonar
// IMU Selection
//
#ifndef SONAR_ENABLED
# define SONAR_ENABLED DISABLED
#ifndef CONFIG_IMU_TYPE
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
#endif
#ifndef SONAR_PIN
# define SONAR_PIN AN4 // AN5, AP_RANGEFINDER_PITOT_TUBE
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
# ifndef CONFIG_MPU6000_CHIP_SELECT_PIN
# define CONFIG_MPU6000_CHIP_SELECT_PIN 53
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// ADC Enable - used to eliminate for systems which don't have ADC.
//
#ifndef CONFIG_ADC
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
# define CONFIG_ADC ENABLED
# else
# define CONFIG_ADC DISABLED
# endif
#endif
//////////////////////////////////////////////////////////////////////////////
// Pitot
//
#ifndef PITOT_ENABLED
# define PITOT_ENABLED DISABLED
#endif
#ifndef CONFIG_PITOT_SOURCE
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ADC
#endif
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
# ifndef CONFIG_PITOT_SOURCE_ADC_CHANNEL
# define CONFIG_PITOT_SOURCE_ADC_CHANNEL 7
# endif
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
# ifndef CONFIG_PITOT_SOURCE_ANALOG_PIN
# define CONFIG_PITOT_SOURCE_ANALOG_PIN AN4
# endif
#else
# warning Invalid value for CONFIG_PITOT_SOURCE, disabling sonar
# undef PITOT_ENABLED
# define PITOT_ENABLED DISABLED
#endif
#ifndef SONAR_TYPE
# define SONAR_TYPE MAX_SONAR_LV // MAX_SONAR_XL,
#endif
/* In ArduPlane PITOT usually takes the place of SONAR, but some bits
* still depend on SONAR.
*/
#define SONAR_ENABLED PITOT_ENABLED
//////////////////////////////////////////////////////////////////////////////
// HIL_MODE OPTIONAL

View File

@ -40,6 +40,7 @@ static void reset_control_switch()
static void update_servo_switches()
{
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
if (!g.switch_enable) {
// switches are disabled in EEPROM (see SWITCH_ENABLE option)
// this means the EEPROM control of all channel reversal is enabled
@ -57,4 +58,5 @@ static void update_servo_switches()
g.reverse_ch1_elevon = (PINE & 64) ? true : false;
g.reverse_ch2_elevon = (PINL & 64) ? true : false;
}
#endif
}

View File

@ -30,6 +30,9 @@
#define SONAR 0
#define BARO 1
#define PITOT_SOURCE_ADC 1
#define PITOT_SOURCE_ANALOG_PIN 2
#define T6 1000000
#define T7 10000000
@ -201,14 +204,6 @@ enum gcs_severity {
#define AN4 4
#define AN5 5
// Hardware Parameters
#define SLIDE_SWITCH_PIN 40
#define PUSHBUTTON_PIN 41
#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C
#define B_LED_PIN 36
#define C_LED_PIN 35
#define SPEEDFILT 400 // centimeters/second; the speed below which a groundstart will be triggered
@ -227,4 +222,10 @@ enum gcs_severity {
// mark a function as not to be inlined
#define NOINLINE __attribute__((noinline))
#define CONFIG_IMU_OILPAN 1
#define CONFIG_IMU_MPU6000 2
#define APM_HARDWARE_APM1 1
#define APM_HARDWARE_APM2 2
#endif // _DEFINES_H

View File

@ -17,6 +17,7 @@ static void failsafe_short_on_event()
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.short_fs_action == 1) {
set_mode(RTL);
@ -47,6 +48,7 @@ static void failsafe_long_on_event()
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.long_fs_action == 1) {
set_mode(RTL);

View File

@ -26,14 +26,21 @@ static int8_t
planner_gcs(uint8_t argc, const Menu::arg *argv)
{
gcs0.init(&Serial);
#if USB_MUX_PIN > 0
// we don't have gcs3 if we have the USB mux setup
gcs3.init(&Serial3);
#endif
int loopcount = 0;
while (1) {
if (millis()-fast_loopTimer > 19) {
fast_loopTimer = millis();
gcs_update();
read_radio();
gcs_data_stream_send(45,1000);
if ((loopcount % 5) == 0) // 10 hz
gcs_data_stream_send(5,45);

View File

@ -43,7 +43,7 @@ static void init_rc_out()
APM_RC.OutputCh(CH_7, g.rc_7.radio_trim);
APM_RC.OutputCh(CH_8, g.rc_8.radio_trim);
APM_RC.Init(); // APM Radio initialization
APM_RC.Init( &isr_registry ); // APM Radio initialization
APM_RC.OutputCh(CH_1, g.channel_roll.radio_trim); // Initialization of servo outputs
APM_RC.OutputCh(CH_2, g.channel_pitch.radio_trim);

View File

@ -31,16 +31,16 @@ static void init_barometer(void)
mavlink_delay(20);
if(flashcount == 5) {
digitalWrite(C_LED_PIN, LOW);
digitalWrite(A_LED_PIN, HIGH);
digitalWrite(B_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
digitalWrite(A_LED_PIN, LED_ON);
digitalWrite(B_LED_PIN, LED_OFF);
}
if(flashcount >= 10) {
flashcount = 0;
digitalWrite(C_LED_PIN, HIGH);
digitalWrite(A_LED_PIN, LOW);
digitalWrite(B_LED_PIN, HIGH);
digitalWrite(C_LED_PIN, LED_ON);
digitalWrite(A_LED_PIN, LED_OFF);
digitalWrite(B_LED_PIN, LED_ON);
}
flashcount++;
}

View File

@ -55,6 +55,24 @@ static void run_cli(void)
static void init_ardupilot()
{
#if USB_MUX_PIN > 0
// on the APM2 board we have a mux thet switches UART0 between
// USB and the board header. If the right ArduPPM firmware is
// installed we can detect if USB is connected using the
// USB_MUX_PIN
pinMode(USB_MUX_PIN, INPUT);
usb_connected = !digitalRead(USB_MUX_PIN);
if (!usb_connected) {
// USB is not connected, this means UART0 may be a Xbee, with
// its darned bricking problem. We can't write to it for at
// least one second after powering up. Simplest solution for
// now is to delay for 1 second. Something more elegant may be
// added later
delay(1000);
}
#endif
// Console serial port
//
// The console port buffers are defined to be sufficiently large to support
@ -82,6 +100,19 @@ static void init_ardupilot()
"\n\nFree RAM: %u\n"),
memcheck_available_memory());
//
// Initialize the ISR registry.
//
isr_registry.init();
//
// Initialize the timer scheduler to use the ISR registry.
//
#if HIL_MODE != HIL_MODE_ATTITUDE
timer_scheduler.init( & isr_registry );
#endif
//
// Check the EEPROM format version before loading any parameters from EEPROM.
//
@ -123,22 +154,33 @@ static void init_ardupilot()
// used to detect in-flight resets
g.num_resets.set_and_save(g.num_resets+1);
// Telemetry port.
//
// Not used if telemetry is going to the console.
//
// XXX for unidirectional protocols, we could (should) minimize
// the receive buffer, and the transmit buffer could also be
// shrunk for protocols that don't send large messages.
//
Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
// init the GCS
gcs0.init(&Serial);
#if USB_MUX_PIN > 0
if (!usb_connected) {
// we are not connected via USB, re-init UART0 with right
// baud rate
Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
}
#else
// we have a 2nd serial port for telemetry
Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
gcs3.init(&Serial3);
#endif
mavlink_system.sysid = g.sysid_this_mav;
#if HIL_MODE != HIL_MODE_ATTITUDE
adc.Init(); // APM ADC library initialization
barometer.Init(); // APM Abs Pressure sensor initialization
adc.Init(&timer_scheduler); // APM ADC library initialization
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
barometer.Init(1, true);
#else
barometer.Init(1, false);
#endif
if (g.compass_enabled==true) {
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
@ -150,13 +192,6 @@ static void init_ardupilot()
compass.get_offsets(); // load offsets to account for airframe magnetic interference
}
}
/*
Init is depricated - Jason
if(g.sonar_enabled){
sonar.init(SONAR_PIN, &adc);
Serial.print("Sonar init: "); Serial.println(SONAR_PIN, DEC);
}
*/
#endif
#if LOGGING_ENABLED == ENABLED
@ -168,25 +203,28 @@ static void init_ardupilot()
g_gps->init(); // GPS Initialization
g_gps->callback = mavlink_delay;
// init the GCS
gcs0.init(&Serial);
gcs3.init(&Serial3);
//mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav
mavlink_system.compid = 1; //MAV_COMP_ID_IMU; // We do not check for comp id
mavlink_system.type = MAV_FIXED_WING;
rc_override_active = APM_RC.setHIL(rc_override); // Set initial values for no override
RC_Channel::set_apm_rc( &APM_RC ); // Provide reference to RC outputs.
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up the timer libs
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
pinMode(A_LED_PIN, OUTPUT); // GPS status LED
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
#if SLIDE_SWITCH_PIN > 0
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
#endif
#if CONFIG_PUSHBUTTON == ENABLED
pinMode(PUSHBUTTON_PIN, INPUT); // unused
#endif
#if CONFIG_RELAY == ENABLED
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
#endif
// If the switch is in 'menu' mode, run the main menu.
//
// Since we can't be sure that the setup or test mode won't leave
@ -195,7 +233,7 @@ static void init_ardupilot()
//
#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
if (digitalRead(SLIDE_SWITCH_PIN) == 0) {
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
digitalWrite(A_LED_PIN,LED_ON); // turn on setup-mode LED
Serial.printf_P(PSTR("\n"
"Entering interactive setup mode...\n"
"\n"
@ -224,7 +262,7 @@ static void init_ardupilot()
//----------------
//read_EEPROM_airstart_critical();
#if HIL_MODE != HIL_MODE_ATTITUDE
imu.init(IMU::WARM_START);
imu.init(IMU::WARM_START, mavlink_delay, &timer_scheduler);
dcm.set_centripetal(1);
#endif
@ -418,7 +456,7 @@ static void startup_IMU_ground(void)
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning IMU calibration; do not move plane"));
mavlink_delay(1000);
imu.init(IMU::COLD_START, mavlink_delay);
imu.init(IMU::COLD_START, mavlink_delay, &timer_scheduler);
dcm.set_centripetal(1);
// read Baro pressure at ground
@ -436,9 +474,9 @@ static void startup_IMU_ground(void)
#endif // HIL_MODE_ATTITUDE
digitalWrite(B_LED_PIN, HIGH); // Set LED B high to indicate IMU ready
digitalWrite(A_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LOW);
digitalWrite(B_LED_PIN, LED_ON); // Set LED B high to indicate IMU ready
digitalWrite(A_LED_PIN, LED_OFF);
digitalWrite(C_LED_PIN, LED_OFF);
}
@ -448,23 +486,23 @@ static void update_GPS_light(void)
// ---------------------------------------------------------------------
switch (g_gps->status()) {
case(2):
digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix.
digitalWrite(C_LED_PIN, LED_ON); //Turn LED C on when gps has valid fix.
break;
case(1):
if (g_gps->valid_read == true){
GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock
if (GPS_light){
digitalWrite(C_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
} else {
digitalWrite(C_LED_PIN, HIGH);
digitalWrite(C_LED_PIN, LED_ON);
}
g_gps->valid_read = false;
}
break;
default:
digitalWrite(C_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
break;
}
}
@ -499,3 +537,22 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
Serial.println_P(PSTR("Invalid SERIAL3_BAUD"));
return default_baud;
}
#if USB_MUX_PIN > 0
static void check_usb_mux(void)
{
bool usb_check = !digitalRead(USB_MUX_PIN);
if (usb_check == usb_connected) {
return;
}
// the user has switched to/from the telemetry port
usb_connected = usb_check;
if (usb_connected) {
Serial.begin(SERIAL0_BAUD, 128, 128);
} else {
Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
}
}
#endif

View File

@ -6,9 +6,12 @@
// are defined below. Order matters to the compiler.
static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv);
static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
static int8_t test_passthru(uint8_t argc, const Menu::arg *argv);
static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv);
static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
#if CONFIG_ADC == ENABLED
static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
#endif
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
static int8_t test_gyro(uint8_t argc, const Menu::arg *argv);
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
@ -22,7 +25,9 @@ static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv);
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
static int8_t test_dipswitches(uint8_t argc, const Menu::arg *argv);
#endif
// Creates a constant array of structs representing menu options
// and stores them in Flash memory, not RAM.
@ -31,6 +36,7 @@ static int8_t test_dipswitches(uint8_t argc, const Menu::arg *argv);
static const struct Menu::command test_menu_commands[] PROGMEM = {
{"pwm", test_radio_pwm},
{"radio", test_radio},
{"passthru", test_passthru},
{"failsafe", test_failsafe},
{"battery", test_battery},
{"relay", test_relay},
@ -38,12 +44,16 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
{"xbee", test_xbee},
{"eedump", test_eedump},
{"modeswitch", test_modeswitch},
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
{"dipswitches", test_dipswitches},
#endif
// Tests below here are for hardware sensors only present
// when real sensors are attached or they are emulated
#if HIL_MODE == HIL_MODE_DISABLED
#if CONFIG_ADC == ENABLED
{"adc", test_adc},
#endif
{"gps", test_gps},
{"rawgps", test_rawgps},
{"imu", test_imu},
@ -123,6 +133,33 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
}
}
static int8_t
test_passthru(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
while(1){
delay(20);
// New radio frame? (we could use also if((millis()- timer) > 20)
if (APM_RC.GetState() == 1){
Serial.print("CH:");
for(int i = 0; i < 8; i++){
Serial.print(APM_RC.InputCh(i)); // Print channel values
Serial.print(",");
APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos
}
Serial.println();
}
if (Serial.available() > 0){
return (0);
}
}
return 0;
}
static int8_t
test_radio(uint8_t argc, const Menu::arg *argv)
{
@ -373,6 +410,7 @@ test_modeswitch(uint8_t argc, const Menu::arg *argv)
}
}
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
static int8_t
test_dipswitches(uint8_t argc, const Menu::arg *argv)
{
@ -403,16 +441,22 @@ test_dipswitches(uint8_t argc, const Menu::arg *argv)
}
}
}
#endif // CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
//-------------------------------------------------------------------------------------------
// tests in this section are for real sensors or sensors that have been simulated
#if HIL_MODE == HIL_MODE_DISABLED || HIL_MODE == HIL_MODE_SENSORS
#if CONFIG_ADC == ENABLED
static int8_t
test_adc(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
adc.Init();
isr_registry.init();
timer_scheduler.init( &isr_registry );
adc.Init(&timer_scheduler);
delay(1000);
Serial.printf_P(PSTR("ADC\n"));
delay(1000);
@ -426,6 +470,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
}
}
}
#endif // CONFIG_ADC
static int8_t
test_gps(uint8_t argc, const Menu::arg *argv)
@ -461,8 +506,9 @@ static int8_t
test_imu(uint8_t argc, const Menu::arg *argv)
{
//Serial.printf_P(PSTR("Calibrating."));
imu.init(IMU::COLD_START);
isr_registry.init();
timer_scheduler.init( &isr_registry );
imu.init(IMU::COLD_START, delay, &timer_scheduler);
print_hit_enter();
delay(1000);
@ -505,7 +551,9 @@ static int8_t
test_gyro(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
adc.Init();
isr_registry.init();
timer_scheduler.init(&isr_registry);
adc.Init(&timer_scheduler);
delay(1000);
Serial.printf_P(PSTR("Gyro | Accel\n"));
delay(1000);
@ -547,7 +595,9 @@ test_mag(uint8_t argc, const Menu::arg *argv)
report_compass();
// we need the DCM initialised for this test
imu.init(IMU::COLD_START);
isr_registry.init();
timer_scheduler.init( &isr_registry );
imu.init(IMU::COLD_START, delay, &timer_scheduler);
int counter = 0;
//Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION);
@ -669,14 +719,14 @@ test_rawgps(uint8_t argc, const Menu::arg *argv)
while(1){
if (Serial3.available()){
digitalWrite(B_LED_PIN, HIGH); // Blink Yellow LED if we are sending data to GPS
digitalWrite(B_LED_PIN, LED_ON); // Blink Yellow LED if we are sending data to GPS
Serial1.write(Serial3.read());
digitalWrite(B_LED_PIN, LOW);
digitalWrite(B_LED_PIN, LED_OFF);
}
if (Serial1.available()){
digitalWrite(C_LED_PIN, HIGH); // Blink Red LED if we are receiving data from GPS
digitalWrite(C_LED_PIN, LED_ON); // Blink Red LED if we are receiving data from GPS
Serial3.write(Serial1.read());
digitalWrite(C_LED_PIN, LOW);
digitalWrite(C_LED_PIN, LED_OFF);
}
if(Serial.available() > 0){
return (0);

View File

@ -1,7 +1,8 @@
Arducoder is the new 8 channels ppm encoder code for ArduPilot Mega / Arducopter boards.
It is compatible with APM v1.x board (ATMEGA 328p), Phonedrone and futur boards using ATmega32u2
ArduPPM is a new 8 channels ppm encoder firmware.
It is compatible with APM v1.x board (ATMEGA 328p), Phonedrone (using ATmega32u2) and futur boards.
Emphasis has been put on code simplicity and reliability.
@ -13,18 +14,19 @@ Emphasis has been put on code simplicity and reliability.
--------------------------------------------------------------------------------------------------
--------------------------------------------------
Warning - Warning - Warning - Warning
Warning
--------------------------------------------------
Code has not yet been extensively tested in the field.
Code has not yet been massively tested in the field.
Nevertheless extensive tests have been done in the lab with a limited set of different receivers, and a limited number of users did report very sucessfull results.
Nevertheless extensive tests have been done in the lab with a limited set of different receivers.
Carefully check that your radio is working perfectly before you fly.
If you see the blue status LED blinking blinking very fast, this is an indication that something is wrong in the decoding.
If you see the blue status LED blinking very fast very often, this is an indication that something is wrong in the decoding. Rare decoding errors do not hurt.
If you have problems, please report the problem and what brand/modell receiver you are using.
@ -44,10 +46,12 @@ Blue status LED is used for status reports :
------------------------------------------
Passthrough mode (mux)
Radio Passthrough mode (mux)
------------------------------------------
Passthrough mode is trigged by channel 8 > 1800 us.
This mode is described as hardware failsafe in Arduplane terminology.
Radio Passthrough mode is trigged by channel 8 > 1800 us.
Blue status LED has different behavior in passthrough mode :
@ -64,7 +68,9 @@ If all contact with the receiver is lost, an internal failsafe is trigged after
Default failsafe values are :
Throttle channel low (channel 3 = 1000 us)
Throttle channel low (channel 3 = 900 us)
Mode Channel set to flight mode 4 (channel 5 = 1555 us)
All other channels set to midstick (1500 us)

View File

@ -10,7 +10,7 @@
<AppDesignerFolder>Properties</AppDesignerFolder>
<RootNamespace>ArdupilotMega</RootNamespace>
<AssemblyName>ArdupilotMegaPlanner</AssemblyName>
<TargetFrameworkVersion>v4.0</TargetFrameworkVersion>
<TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
<TargetFrameworkProfile>
</TargetFrameworkProfile>
<FileAlignment>512</FileAlignment>
@ -136,14 +136,11 @@
</Reference>
<Reference Include="IronPython, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython.dll</HintPath>
<Private>True</Private>
<EmbedInteropTypes>False</EmbedInteropTypes>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\IronPython.dll</HintPath>
</Reference>
<Reference Include="IronPython.Modules, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython.Modules.dll</HintPath>
<Private>True</Private>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\IronPython.Modules.dll</HintPath>
</Reference>
<Reference Include="KMLib">
<HintPath>..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\KMLib.dll</HintPath>
@ -158,15 +155,22 @@
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.DirectInput.dll</HintPath>
<Private>False</Private>
</Reference>
<Reference Include="Microsoft.Dynamic, Version=1.1.0.20, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\Microsoft.Dynamic.dll</HintPath>
<Private>True</Private>
<Reference Include="Microsoft.Dynamic">
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Dynamic.dll</HintPath>
</Reference>
<Reference Include="Microsoft.Scripting, Version=1.1.0.20, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\Microsoft.Scripting.dll</HintPath>
<Private>True</Private>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.dll</HintPath>
</Reference>
<Reference Include="Microsoft.Scripting.Core">
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.Core.dll</HintPath>
</Reference>
<Reference Include="Microsoft.Scripting.Debugging">
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.Debugging.dll</HintPath>
</Reference>
<Reference Include="Microsoft.Scripting.ExtensionAttribute, Version=2.0.0.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.ExtensionAttribute.dll</HintPath>
</Reference>
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
@ -218,6 +222,12 @@
</Compile>
<Compile Include="CommsTCPSerial.cs" />
<Compile Include="CommsUdpSerial.cs" />
<Compile Include="ResEdit.cs">
<SubType>Form</SubType>
</Compile>
<Compile Include="ResEdit.Designer.cs">
<DependentUpon>ResEdit.cs</DependentUpon>
</Compile>
<Compile Include="georefimage.cs" />
<Compile Include="HIL\Aircraft.cs" />
<Compile Include="HIL\Point3d.cs" />
@ -384,6 +394,9 @@
<EmbeddedResource Include="Camera.resx">
<DependentUpon>Camera.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="ResEdit.resx">
<DependentUpon>ResEdit.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Configuration.ru-RU.resx">
<DependentUpon>Configuration.cs</DependentUpon>
</EmbeddedResource>
@ -425,7 +438,6 @@
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Configuration.resx">
<DependentUpon>Configuration.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Configuration.zh-Hans.resx">
@ -446,21 +458,18 @@
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Help.resx">
<DependentUpon>Help.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Help.zh-Hans.resx">
<DependentUpon>Help.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Simulation.resx">
<DependentUpon>Simulation.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Simulation.zh-Hans.resx">
<DependentUpon>Simulation.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Terminal.resx">
<DependentUpon>Terminal.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Terminal.zh-Hans.resx">
<DependentUpon>Terminal.cs</DependentUpon>
@ -473,7 +482,6 @@
</EmbeddedResource>
<EmbeddedResource Include="JoystickSetup.resx">
<DependentUpon>JoystickSetup.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</EmbeddedResource>
<EmbeddedResource Include="JoystickSetup.zh-Hans.resx">
<DependentUpon>JoystickSetup.cs</DependentUpon>
@ -483,17 +491,14 @@
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Firmware.resx">
<DependentUpon>Firmware.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\FlightData.resx">
<DependentUpon>FlightData.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\FlightPlanner.resx">
<DependentUpon>FlightPlanner.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="ElevationProfile.resx">
@ -520,7 +525,6 @@
</EmbeddedResource>
<EmbeddedResource Include="Setup\Setup.resx">
<DependentUpon>Setup.cs</DependentUpon>
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</EmbeddedResource>
<EmbeddedResource Include="Setup\Setup.zh-Hans.resx">
<DependentUpon>Setup.cs</DependentUpon>

View File

@ -11,6 +11,6 @@
<UpdateUrlHistory />
</PropertyGroup>
<PropertyGroup>
<ReferencePath>C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Release\</ReferencePath>
<ReferencePath>C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\;C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Release\</ReferencePath>
</PropertyGroup>
</Project>

View File

@ -5,8 +5,6 @@ Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArdupilotMega", "ArdupilotM
EndProject
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "Updater", "Updater\Updater.csproj", "{E64A1A41-A5B0-458E-8284-BB63705354DA}"
EndProject
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "resedit", "resedit\resedit.csproj", "{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}"
EndProject
Global
GlobalSection(SolutionConfigurationPlatforms) = preSolution
Debug|Any CPU = Debug|Any CPU
@ -43,18 +41,6 @@ Global
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Win32.ActiveCfg = Release|x86
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.ActiveCfg = Release|x86
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.Build.0 = Release|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Any CPU.ActiveCfg = Debug|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Mixed Platforms.Build.0 = Debug|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|Win32.ActiveCfg = Debug|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|x86.ActiveCfg = Debug|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Debug|x86.Build.0 = Debug|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Any CPU.ActiveCfg = Release|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Mixed Platforms.ActiveCfg = Release|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Mixed Platforms.Build.0 = Release|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|Win32.ActiveCfg = Release|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|x86.ActiveCfg = Release|x86
{BAD1CB95-CD73-44D3-ADF0-00EDFA844FB9}.Release|x86.Build.0 = Release|x86
EndGlobalSection
GlobalSection(SolutionProperties) = preSolution
HideSolutionNode = FALSE

View File

@ -3,6 +3,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex</url2560-2>
<name>ArduPlane V2.26 </name>
<desc></desc>
<format_version>12</format_version>
@ -10,6 +11,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex</url2560-2>
<name>ArduPlane V2.26 HIL</name>
<desc>
#define FLIGHT_MODE_CHANNEL 8
@ -44,6 +46,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560-2.hex</url2560-2>
<name>ArduPlane V2.26 APM trunk</name>
<desc></desc>
<format_version>12</format_version>
@ -51,6 +54,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Quad</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
@ -62,6 +66,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Tri</name>
<desc>
#define FRAME_CONFIG TRI_FRAME
@ -73,6 +78,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Hexa</name>
<desc>
#define FRAME_CONFIG HEXA_FRAME
@ -84,6 +90,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Y6</name>
<desc>
#define FRAME_CONFIG Y6_FRAME
@ -95,6 +102,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Heli (2560 only)</name>
<desc>
#define AUTO_RESET_LOITER 0
@ -142,6 +150,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Quad Hil</name>
<desc>
#define FRAME_CONFIG QUAD_FRAME
@ -157,6 +166,7 @@
<Firmware>
<url>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>
<url2560>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex</url2560>
<url2560-2>http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560-2.hex</url2560-2>
<name>ArduCopter V2.0.50 Beta Heli Hil</name>
<desc>

View File

@ -1 +1,362 @@
Already up-to-date.
From https://code.google.com/p/ardupilot-mega
0b42d33..e4850de master -> origin/master
* [new tag] 2.0.50_Beta -> 2.0.50_Beta
From https://code.google.com/p/ardupilot-mega
* [new tag] ArduCopter-2.1.0-Alpha -> ArduCopter-2.1.0-Alpha
* [new tag] ArduPlane-2.27-Alpha -> ArduPlane-2.27-Alpha
* [new tag] pre-apm2-support -> pre-apm2-support
Updating 0b42d33..e4850de
Fast-forward
.gitignore | 2 +
ArduBoat/ControllerBoat.h | 10 +-
ArduCopter/APM_Config.h | 7 +-
ArduCopter/ArduCopter.pde | 98 +-
ArduCopter/GCS.h | 8 +-
ArduCopter/GCS_Mavlink.pde | 29 +-
ArduCopter/Log.pde | 395 +-
ArduCopter/Makefile | 27 +
ArduCopter/config.h | 126 +-
ArduCopter/defines.h | 19 +-
ArduCopter/heli.pde | 4 +-
ArduCopter/leds.pde | 32 +-
ArduCopter/motors.pde | 4 +-
ArduCopter/motors_hexa.pde | 5 +-
ArduCopter/motors_octa.pde | 5 +-
ArduCopter/motors_octa_quad.pde | 5 +-
ArduCopter/motors_quad.pde | 4 +-
ArduCopter/motors_tri.pde | 4 +-
ArduCopter/motors_y6.pde | 5 +-
ArduCopter/planner.pde | 2 +
ArduCopter/radio.pde | 48 +-
ArduCopter/setup.pde | 26 -
ArduCopter/system.pde | 154 +-
ArduCopter/test.pde | 164 +-
ArduPlane/APM_Config.h | 1 -
ArduPlane/ArduPlane.pde | 83 +-
ArduPlane/GCS.h | 8 +-
ArduPlane/GCS_Mavlink.pde | 29 +-
ArduPlane/Log.pde | 265 +-
ArduPlane/Makefile | 27 +
ArduPlane/config.h | 95 +-
ArduPlane/control_modes.pde | 2 +
ArduPlane/defines.h | 17 +-
ArduPlane/planner.pde | 9 +-
ArduPlane/radio.pde | 2 +-
ArduPlane/sensors.pde | 12 +-
ArduPlane/system.pde | 146 +-
ArduPlane/test.pde | 68 +-
ArduRover/ControllerCar.h | 8 +-
ArduRover/ControllerTank.h | 2 +-
CMakeLists.txt | 12 +-
README.txt | 20 +-
Tools/ArduPPM/ATMega328p/Encoder-PPM.c | 18 +-
Tools/ArduPPM/ATMega328p/Encoder-PPM.hex | 111 -
Tools/ArduPPM/ATMega328p/manual.txt | 24 +-
Tools/ArdupilotMegaPlanner/ArduinoDetect.cs | 4 +-
Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 48 +-
.../ArdupilotMegaPlanner/ArdupilotMega.csproj.user | 3 +
Tools/ArdupilotMegaPlanner/ArdupilotMega.sln | 14 -
Tools/ArdupilotMegaPlanner/Common.cs | 14 +-
.../GCSViews/Configuration.Designer.cs | 464 +-
.../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 26 +-
.../GCSViews/Configuration.resx | 5322 ++++++++++++-----
.../GCSViews/Configuration.zh-Hans.resx | 88 +-
Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 4 +-
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 2 +-
.../GCSViews/FlightData.zh-Hans.resx | 140 +-
.../GCSViews/FlightPlanner.Designer.cs | 11 +
.../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 53 +-
.../GCSViews/FlightPlanner.resx | 110 +-
.../GCSViews/FlightPlanner.zh-Hans.resx | 4 +
.../GCSViews/Simulation.zh-Hans.resx | 30 +-
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 7 -
Tools/ArdupilotMegaPlanner/HIL/Aircraft.cs | 1 -
Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs | 5 +
Tools/ArdupilotMegaPlanner/MAVLink.cs | 116 +-
Tools/ArdupilotMegaPlanner/MainV2.cs | 92 +-
Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 9 +-
.../Properties/AssemblyInfo.cs | 2 +-
.../Properties/Resources.Designer.cs | 2 +-
Tools/ArdupilotMegaPlanner/ResEdit.Designer.cs | 162 +
Tools/ArdupilotMegaPlanner/ResEdit.cs | 284 +
.../{bin/Release/HUD.resx => ResEdit.resx} | 326 +-
Tools/ArdupilotMegaPlanner/Script.cs | 135 +
Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 4 +-
.../ArdupilotMegaPlanner/Setup/Setup.zh-Hans.resx | 261 +-
Tools/ArdupilotMegaPlanner/Splash.cs | 1 -
Tools/ArdupilotMegaPlanner/app.config | 7 +-
.../bin/Release/ArduCopter.exe | Bin 681422 -> 746255 bytes
.../ArdupilotMegaPlanner/bin/Release/ArduPlane.exe | Bin 676470 -> 782630 bytes
.../bin/Release/ArdupilotMegaPlanner.application | 4 +-
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2214400 -> 2191360 bytes
.../bin/Release/ArdupilotMegaPlanner.exe.config | 7 +-
.../bin/Release/BSE.Windows.Forms.dll | Bin 141824 -> 141824 bytes
.../bin/Release/GCSViews/Configuration.resx | 6431 --------------------
.../bin/Release/GCSViews/Firmware.resx | 705 ---
.../bin/Release/GCSViews/FlightData.resx | 1828 ------
.../bin/Release/GCSViews/FlightPlanner.resx | 2110 -------
.../bin/Release/GCSViews/Help.resx | 228 -
.../bin/Release/GCSViews/Simulation.resx | 2100 -------
.../bin/Release/GCSViews/Terminal.resx | 289 -
.../bin/Release/GMap.NET.Core.dll | Bin 183808 -> 184320 bytes
.../bin/Release/GMap.NET.WindowsForms.dll | Bin 77824 -> 77824 bytes
.../bin/Release/IronPython.Modules.dll | Bin 0 -> 464728 bytes
.../bin/Release/IronPython.dll | Bin 0 -> 1496920 bytes
.../bin/Release/JoystickSetup.resx | 1807 ------
.../bin/Release/Microsoft.Dynamic.dll | Bin 0 -> 956248 bytes
.../bin/Release/Microsoft.Scripting.Core.dll | Bin 0 -> 403288 bytes
.../bin/Release/Microsoft.Scripting.Debugging.dll | Bin 0 -> 58200 bytes
.../Microsoft.Scripting.ExtensionAttribute.dll | Bin 0 -> 11096 bytes
.../bin/Release/Microsoft.Scripting.dll | Bin 0 -> 178008 bytes
.../bin/Release/Setup/Setup.resx | 3751 ------------
.../ArdupilotMegaPlanner/bin/Release/SharpKml.dll | Bin 124928 -> 124928 bytes
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
.../bin/Release/arducopter-xplane.zip | Bin 0 -> 169744 bytes
.../bin/Release/dataflashlog.xml | 260 +-
Tools/ArdupilotMegaPlanner/bin/Release/mavcmd.xml | 532 ++-
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 0 bytes
.../bin/Release/resedit.exe.config | 3 -
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 417792 bytes
Tools/ArdupilotMegaPlanner/dataflashlog.xml | 260 +-
Tools/ArdupilotMegaPlanner/hires.cs | 48 +
Tools/ArdupilotMegaPlanner/mavcmd.xml | 532 ++-
Tools/ArdupilotMegaPlanner/mykey.snk | Bin 0 -> 596 bytes
Tools/ArdupilotMegaPlanner/resedit/Form1.cs | 18 +
Tools/ArdupilotMegaPlanner/temp.Designer.cs | 13 +
Tools/ArdupilotMegaPlanner/temp.cs | 5 +
Tools/PPMEncoder/ap_ppm_encoder.aps | 1 -
Tools/PPMEncoder/ap_ppm_encoder.aws | 1 -
Tools/PPMEncoder/ap_ppm_encoder.c | 1286 ----
Tools/PPMEncoder/default/Makefile | 77 -
Tools/PPMEncoder/default/ap_ppm_encoder.eep | 5 -
Tools/PPMEncoder/default/ap_ppm_encoder.elf | Bin 16459 -> 0 bytes
Tools/PPMEncoder/default/ap_ppm_encoder.hex | 197 -
Tools/PPMEncoder/default/ap_ppm_encoder.lss | 2636 --------
Tools/PPMEncoder/default/ap_ppm_encoder.map | 419 --
Tools/PPMEncoder/default/dep/ap_ppm_encoder.o.d | 46 -
Tools/PPMEncoder/default/ppm_enconder_at328.bat | 17 -
Tools/PPMEncoder/servo2ppm_settings.h | 128 -
Tools/autotest/ArduCopter.parm | 1 +
Tools/autotest/arducopter.py | 26 +-
Tools/autotest/autotest.py | 22 +-
Tools/autotest/common.py | 3 +-
Tools/autotest/util.py | 6 +-
Tools/scripts/build_all.sh | 25 +
apo/ControllerPlane.h | 10 +-
apo/ControllerQuad.h | 53 +-
apo/QuadArducopter.h | 25 +-
apo/apo.pde | 5 +-
cmake/modules/FindArduino.cmake | 227 +-
cmake/toolchains/Arduino.cmake | 6 +-
cmake/updated-arduino-cmake.sh | 2 +-
libraries/APM_BMP085/APM_BMP085.cpp | 32 +-
libraries/APM_BMP085/APM_BMP085.h | 7 +-
libraries/APM_BMP085/APM_BMP085_hil.cpp | 2 +-
libraries/APM_BMP085/APM_BMP085_hil.h | 3 +-
.../examples/APM_BMP085_test/APM_BMP085_test.pde | 13 +-
.../APM_BMP085/examples/APM_BMP085_test/Makefile | 3 +
libraries/APM_RC/APM_RC.h | 53 +-
libraries/APM_RC/{APM_RC.cpp => APM_RC_APM1.cpp} | 548 +-
libraries/APM_RC/APM_RC_APM1.h | 43 +
libraries/APM_RC/APM_RC_APM2.cpp | 289 +
libraries/APM_RC/APM_RC_APM2.h | 42 +
.../APM_radio.pde => APM1_radio/APM1_radio.pde} | 11 +-
.../AP_IMU => APM_RC/examples/APM1_radio}/Makefile | 2 +-
.../APM_RC/examples/{APM_radio => APM2}/Makefile | 2 +-
.../APM_radio.pde => APM2/Purple_radio.pde} | 11 +-
libraries/APO/APO.h | 1 +
libraries/APO/AP_ArmingMechanism.cpp | 16 +-
libraries/APO/AP_ArmingMechanism.h | 8 +-
libraries/APO/AP_Autopilot.cpp | 7 +-
libraries/APO/AP_CommLink.cpp | 139 +-
libraries/APO/AP_Controller.cpp | 104 +-
libraries/APO/AP_Controller.h | 368 +-
libraries/APO/AP_ControllerBlock.cpp | 179 +
libraries/APO/AP_ControllerBlock.h | 237 +
libraries/APO/AP_Guide.cpp | 37 +-
libraries/APO/AP_Guide.h | 26 +-
libraries/APO/AP_HardwareAbstractionLayer.h | 10 +-
libraries/APO/AP_MavlinkCommand.cpp | 4 +-
libraries/APO/AP_Navigator.cpp | 5 +-
libraries/APO/AP_Navigator.h | 103 +-
libraries/AP_ADC/AP_ADC.h | 4 +-
libraries/AP_ADC/AP_ADC_ADS7844.cpp | 76 +-
libraries/AP_ADC/AP_ADC_ADS7844.h | 4 +-
libraries/AP_ADC/AP_ADC_HIL.cpp | 2 +-
libraries/AP_ADC/AP_ADC_HIL.h | 2 +-
.../AP_ADC/examples/AP_ADC_test/AP_ADC_test.pde | 14 +-
libraries/AP_ADC/examples/AP_ADC_test/Makefile | 2 +-
libraries/AP_AnalogSource/AP_AnalogSource.h | 8 +
libraries/AP_AnalogSource/AP_AnalogSource_ADC.cpp | 9 +
libraries/AP_AnalogSource/AP_AnalogSource_ADC.h | 21 +
.../AP_AnalogSource/AP_AnalogSource_Arduino.cpp | 8 +
.../AP_AnalogSource/AP_AnalogSource_Arduino.h | 17 +
libraries/AP_AnalogSource/AnalogSource.h | 11 +
libraries/AP_Common/AP_Common.h | 34 +-
libraries/AP_Common/AP_Vector.h | 1 +
libraries/AP_Common/Arduino.mk | 7 +-
libraries/AP_Common/include/menu.h | 2 +
libraries/AP_Compass/AP_Compass_HMC5843.h | 1 +
libraries/AP_IMU/AP_IMU.h | 3 +-
libraries/AP_IMU/AP_IMU_INS.cpp | 250 +
libraries/AP_IMU/AP_IMU_INS.h | 84 +
libraries/AP_IMU/AP_IMU_Oilpan.cpp | 302 -
libraries/AP_IMU/AP_IMU_Oilpan.h | 109 -
libraries/AP_IMU/AP_IMU_Shim.h | 5 +-
libraries/AP_IMU/IMU.cpp | 34 +
libraries/AP_IMU/IMU.h | 23 +-
.../examples/AP_IMU_MPU6000/AP_IMU_MPU6000.pde | 55 +
.../examples/AP_IMU_MPU6000}/Makefile | 0
.../examples/IMU_MPU6000_test/IMU_MPU6000_test.pde | 50 +
.../examples/IMU_MPU6000_test}/Makefile | 2 +-
.../IMU_Oilpan_test.pde} | 22 +-
.../examples/IMU_Oilpan_test}/Makefile | 2 +-
libraries/AP_InertialSensor/AP_InertialSensor.h | 62 +
.../AP_InertialSensor_MPU6000.cpp | 298 +
.../AP_InertialSensor/AP_InertialSensor_MPU6000.h | 67 +
.../AP_InertialSensor/AP_InertialSensor_Oilpan.cpp | 122 +
.../AP_InertialSensor/AP_InertialSensor_Oilpan.h | 60 +
.../AP_InertialSensor/AP_InertialSensor_Stub.cpp | 26 +
.../AP_InertialSensor/AP_InertialSensor_Stub.h | 35 +
libraries/AP_PeriodicProcess/AP_PeriodicProcess.h | 10 +
.../AP_PeriodicProcess/AP_PeriodicProcessStub.cpp | 6 +
.../AP_PeriodicProcess/AP_PeriodicProcessStub.h | 21 +
.../AP_TimerAperiodicProcess.cpp | 39 +
.../AP_PeriodicProcess/AP_TimerAperiodicProcess.h | 19 +
libraries/AP_PeriodicProcess/AP_TimerProcess.cpp | 43 +
libraries/AP_PeriodicProcess/AP_TimerProcess.h | 23 +
libraries/AP_PeriodicProcess/PeriodicProcess.h | 11 +
.../AP_RangeFinder/AP_RangeFinder_MaxsonarXL.cpp | 5 +-
.../AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h | 2 +-
.../AP_RangeFinder/AP_RangeFinder_SharpGP2Y.cpp | 5 +-
.../AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h | 2 +-
libraries/AP_RangeFinder/RangeFinder.cpp | 17 +-
libraries/AP_RangeFinder/RangeFinder.h | 14 +-
.../AP_RangeFinder_test/AP_RangeFinder_test.pde | 6 +-
libraries/AP_RangeFinder/keywords.txt | 3 +-
.../Arduino_Mega_ISR_Registry.cpp | 48 +
.../Arduino_Mega_ISR_Registry.h | 22 +
libraries/DataFlash/DataFlash.h | 155 +-
.../{DataFlash.cpp => DataFlash_APM1.cpp} | 939 ++--
libraries/DataFlash/DataFlash_APM1.h | 67 +
libraries/DataFlash/DataFlash_APM2.cpp | 495 ++
libraries/DataFlash/DataFlash_APM2.h | 72 +
libraries/Desktop/Desktop.mk | 4 +-
libraries/Desktop/include/avr/iomxx0_1.h | 10 +
libraries/Desktop/include/avr/pgmspace.h | 4 +
libraries/Desktop/support/Arduino.cpp | 17 +-
.../support/{DataFlash.cpp => DataFlash_APM1.cpp} | 122 +-
libraries/Desktop/support/FastSerial.cpp | 36 +-
libraries/Desktop/support/desktop.h | 22 +-
libraries/Desktop/support/main.cpp | 47 +-
libraries/Desktop/support/sitl.cpp | 310 +
libraries/Desktop/support/sitl_adc.cpp | 129 +
libraries/Desktop/support/sitl_adc.h | 68 +
libraries/Desktop/support/sitl_barometer.cpp | 36 +
libraries/Desktop/support/sitl_compass.cpp | 69 +
libraries/Desktop/support/sitl_gps.cpp | 159 +
libraries/Desktop/support/sitl_rc.h | 52 +
libraries/Desktop/support/util.cpp | 92 +
libraries/Desktop/support/util.h | 11 +
libraries/RC_Channel/RC_Channel.cpp | 6 +
libraries/RC_Channel/RC_Channel.h | 3 +
libraries/RC_Channel/RC_Channel_aux.cpp | 2 +-
255 files changed, 14009 insertions(+), 29401 deletions(-)
delete mode 100644 Tools/ArduPPM/ATMega328p/Encoder-PPM.hex
create mode 100644 Tools/ArdupilotMegaPlanner/ResEdit.Designer.cs
create mode 100644 Tools/ArdupilotMegaPlanner/ResEdit.cs
rename Tools/ArdupilotMegaPlanner/{bin/Release/HUD.resx => ResEdit.resx} (70%)
create mode 100644 Tools/ArdupilotMegaPlanner/Script.cs
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Configuration.resx
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Firmware.resx
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightData.resx
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightPlanner.resx
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Help.resx
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Simulation.resx
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Terminal.resx
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/IronPython.Modules.dll
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/IronPython.dll
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/JoystickSetup.resx
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/Microsoft.Dynamic.dll
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/Microsoft.Scripting.Core.dll
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/Microsoft.Scripting.Debugging.dll
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/Microsoft.Scripting.ExtensionAttribute.dll
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/Microsoft.Scripting.dll
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/Setup/Setup.resx
create mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/arducopter-xplane.zip
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe
delete mode 100644 Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe.config
create mode 100644 Tools/ArdupilotMegaPlanner/hires.cs
create mode 100644 Tools/ArdupilotMegaPlanner/mykey.snk
delete mode 100644 Tools/PPMEncoder/ap_ppm_encoder.aps
delete mode 100644 Tools/PPMEncoder/ap_ppm_encoder.aws
delete mode 100644 Tools/PPMEncoder/ap_ppm_encoder.c
delete mode 100644 Tools/PPMEncoder/default/Makefile
delete mode 100644 Tools/PPMEncoder/default/ap_ppm_encoder.eep
delete mode 100644 Tools/PPMEncoder/default/ap_ppm_encoder.elf
delete mode 100644 Tools/PPMEncoder/default/ap_ppm_encoder.hex
delete mode 100644 Tools/PPMEncoder/default/ap_ppm_encoder.lss
delete mode 100644 Tools/PPMEncoder/default/ap_ppm_encoder.map
delete mode 100644 Tools/PPMEncoder/default/dep/ap_ppm_encoder.o.d
delete mode 100644 Tools/PPMEncoder/default/ppm_enconder_at328.bat
delete mode 100644 Tools/PPMEncoder/servo2ppm_settings.h
create mode 100755 Tools/scripts/build_all.sh
rename libraries/APM_RC/{APM_RC.cpp => APM_RC_APM1.cpp} (65%)
create mode 100644 libraries/APM_RC/APM_RC_APM1.h
create mode 100644 libraries/APM_RC/APM_RC_APM2.cpp
create mode 100644 libraries/APM_RC/APM_RC_APM2.h
copy libraries/APM_RC/examples/{APM_radio/APM_radio.pde => APM1_radio/APM1_radio.pde} (75%)
rename libraries/{AP_IMU/examples/AP_IMU => APM_RC/examples/APM1_radio}/Makefile (69%)
copy libraries/APM_RC/examples/{APM_radio => APM2}/Makefile (69%)
rename libraries/APM_RC/examples/{APM_radio/APM_radio.pde => APM2/Purple_radio.pde} (75%)
create mode 100644 libraries/APO/AP_ControllerBlock.cpp
create mode 100644 libraries/APO/AP_ControllerBlock.h
create mode 100644 libraries/AP_AnalogSource/AP_AnalogSource.h
create mode 100644 libraries/AP_AnalogSource/AP_AnalogSource_ADC.cpp
create mode 100644 libraries/AP_AnalogSource/AP_AnalogSource_ADC.h
create mode 100644 libraries/AP_AnalogSource/AP_AnalogSource_Arduino.cpp
create mode 100644 libraries/AP_AnalogSource/AP_AnalogSource_Arduino.h
create mode 100644 libraries/AP_AnalogSource/AnalogSource.h
create mode 100644 libraries/AP_IMU/AP_IMU_INS.cpp
create mode 100644 libraries/AP_IMU/AP_IMU_INS.h
delete mode 100644 libraries/AP_IMU/AP_IMU_Oilpan.cpp
delete mode 100644 libraries/AP_IMU/AP_IMU_Oilpan.h
create mode 100644 libraries/AP_IMU/IMU.cpp
create mode 100644 libraries/AP_IMU/examples/AP_IMU_MPU6000/AP_IMU_MPU6000.pde
copy libraries/{APM_RC/examples/APM_radio => AP_IMU/examples/AP_IMU_MPU6000}/Makefile (100%)
create mode 100644 libraries/AP_IMU/examples/IMU_MPU6000_test/IMU_MPU6000_test.pde
copy libraries/{APM_RC/examples/APM_radio => AP_IMU/examples/IMU_MPU6000_test}/Makefile (69%)
rename libraries/AP_IMU/examples/{AP_IMU/AP_IMU.pde => IMU_Oilpan_test/IMU_Oilpan_test.pde} (53%)
rename libraries/{APM_RC/examples/APM_radio => AP_IMU/examples/IMU_Oilpan_test}/Makefile (69%)
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor.h
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp
create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_Stub.h
create mode 100644 libraries/AP_PeriodicProcess/AP_PeriodicProcess.h
create mode 100644 libraries/AP_PeriodicProcess/AP_PeriodicProcessStub.cpp
create mode 100644 libraries/AP_PeriodicProcess/AP_PeriodicProcessStub.h
create mode 100644 libraries/AP_PeriodicProcess/AP_TimerAperiodicProcess.cpp
create mode 100644 libraries/AP_PeriodicProcess/AP_TimerAperiodicProcess.h
create mode 100644 libraries/AP_PeriodicProcess/AP_TimerProcess.cpp
create mode 100644 libraries/AP_PeriodicProcess/AP_TimerProcess.h
create mode 100644 libraries/AP_PeriodicProcess/PeriodicProcess.h
create mode 100644 libraries/Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.cpp
create mode 100644 libraries/Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h
rename libraries/DataFlash/{DataFlash.cpp => DataFlash_APM1.cpp} (66%)
create mode 100644 libraries/DataFlash/DataFlash_APM1.h
create mode 100644 libraries/DataFlash/DataFlash_APM2.cpp
create mode 100644 libraries/DataFlash/DataFlash_APM2.h
rename libraries/Desktop/support/{DataFlash.cpp => DataFlash_APM1.cpp} (53%)
create mode 100644 libraries/Desktop/support/sitl.cpp
create mode 100644 libraries/Desktop/support/sitl_adc.cpp
create mode 100644 libraries/Desktop/support/sitl_adc.h
create mode 100644 libraries/Desktop/support/sitl_barometer.cpp
create mode 100644 libraries/Desktop/support/sitl_compass.cpp
create mode 100644 libraries/Desktop/support/sitl_gps.cpp
create mode 100644 libraries/Desktop/support/sitl_rc.h
create mode 100644 libraries/Desktop/support/util.cpp
create mode 100644 libraries/Desktop/support/util.h

View File

@ -30,8 +30,8 @@
{
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
this.Params = new System.Windows.Forms.DataGridView();
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
@ -141,6 +141,13 @@
this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
this.label52 = new System.Windows.Forms.Label();
this.TabAC2 = new System.Windows.Forms.TabPage();
this.groupBox17 = new System.Windows.Forms.GroupBox();
this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
this.label27 = new System.Windows.Forms.Label();
this.ACRO_PIT_I = new System.Windows.Forms.NumericUpDown();
this.label29 = new System.Windows.Forms.Label();
this.ACRO_PIT_P = new System.Windows.Forms.NumericUpDown();
this.label33 = new System.Windows.Forms.Label();
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.label14 = new System.Windows.Forms.Label();
this.THR_RATE_IMAX = new System.Windows.Forms.NumericUpDown();
@ -148,6 +155,13 @@
this.label20 = new System.Windows.Forms.Label();
this.THR_RATE_P = new System.Windows.Forms.NumericUpDown();
this.label25 = new System.Windows.Forms.Label();
this.groupBox18 = new System.Windows.Forms.GroupBox();
this.ACRO_RLL_IMAX = new System.Windows.Forms.NumericUpDown();
this.label40 = new System.Windows.Forms.Label();
this.ACRO_RLL_I = new System.Windows.Forms.NumericUpDown();
this.label44 = new System.Windows.Forms.Label();
this.ACRO_RLL_P = new System.Windows.Forms.NumericUpDown();
this.label48 = new System.Windows.Forms.Label();
this.CHK_lockrollpitch = new System.Windows.Forms.CheckBox();
this.groupBox4 = new System.Windows.Forms.GroupBox();
this.WP_SPEED_MAX = new System.Windows.Forms.NumericUpDown();
@ -159,13 +173,7 @@
this.NAV_LAT_P = new System.Windows.Forms.NumericUpDown();
this.label16 = new System.Windows.Forms.Label();
this.groupBox6 = new System.Windows.Forms.GroupBox();
this.XTRK_ANGLE_CD1 = new System.Windows.Forms.NumericUpDown();
this.label10 = new System.Windows.Forms.Label();
this.XTRACK_IMAX = new System.Windows.Forms.NumericUpDown();
this.label11 = new System.Windows.Forms.Label();
this.XTRACK_I = new System.Windows.Forms.NumericUpDown();
this.label17 = new System.Windows.Forms.Label();
this.XTRACK_P = new System.Windows.Forms.NumericUpDown();
this.XTRK_GAIN_SC1 = new System.Windows.Forms.NumericUpDown();
this.label18 = new System.Windows.Forms.Label();
this.groupBox7 = new System.Windows.Forms.GroupBox();
this.THR_ALT_IMAX = new System.Windows.Forms.NumericUpDown();
@ -275,51 +283,119 @@
this.BUT_load = new ArdupilotMega.MyButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_compare = new ArdupilotMega.MyButton();
this.groupBox17 = new System.Windows.Forms.GroupBox();
this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
this.label27 = new System.Windows.Forms.Label();
this.ACRO_PIT_I = new System.Windows.Forms.NumericUpDown();
this.label29 = new System.Windows.Forms.Label();
this.ACRO_PIT_P = new System.Windows.Forms.NumericUpDown();
this.label33 = new System.Windows.Forms.Label();
this.groupBox18 = new System.Windows.Forms.GroupBox();
this.ACRO_RLL_IMAX = new System.Windows.Forms.NumericUpDown();
this.label40 = new System.Windows.Forms.Label();
this.ACRO_RLL_I = new System.Windows.Forms.NumericUpDown();
this.label44 = new System.Windows.Forms.Label();
this.ACRO_RLL_P = new System.Windows.Forms.NumericUpDown();
this.label48 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
this.ConfigTabs.SuspendLayout();
this.TabAPM2.SuspendLayout();
this.groupBox3.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).BeginInit();
this.groupBox1.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).BeginInit();
this.groupBox2.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).BeginInit();
this.groupBox15.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).BeginInit();
this.groupBox16.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).BeginInit();
this.groupBox14.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).BeginInit();
this.groupBox13.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).BeginInit();
this.groupBox12.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).BeginInit();
this.groupBox11.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).BeginInit();
this.groupBox10.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).BeginInit();
this.groupBox9.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).BeginInit();
this.groupBox8.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).BeginInit();
this.TabAC2.SuspendLayout();
this.groupBox17.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_P)).BeginInit();
this.groupBox5.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).BeginInit();
this.groupBox18.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_P)).BeginInit();
this.groupBox4.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).BeginInit();
this.groupBox6.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC1)).BeginInit();
this.groupBox7.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).BeginInit();
this.groupBox19.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).BeginInit();
this.groupBox20.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).BeginInit();
this.groupBox21.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).BeginInit();
this.groupBox22.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).BeginInit();
this.groupBox23.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).BeginInit();
this.groupBox24.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).BeginInit();
this.groupBox25.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).BeginInit();
this.TabPlanner.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
this.groupBox17.SuspendLayout();
this.groupBox18.SuspendLayout();
this.SuspendLayout();
//
// Params
@ -327,14 +403,14 @@
this.Params.AllowUserToAddRows = false;
this.Params.AllowUserToDeleteRows = false;
resources.ApplyResources(this.Params, "Params");
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle3.BackColor = System.Drawing.Color.Maroon;
dataGridViewCellStyle3.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle3.ForeColor = System.Drawing.Color.White;
dataGridViewCellStyle3.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle3.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle3.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle3;
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.Command,
@ -343,14 +419,14 @@
this.mavScale,
this.RawValue});
this.Params.Name = "Params";
dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle4.BackColor = System.Drawing.SystemColors.ActiveCaption;
dataGridViewCellStyle4.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle4.ForeColor = System.Drawing.SystemColors.WindowText;
dataGridViewCellStyle4.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle4.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle4.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle4;
this.Params.RowHeadersVisible = false;
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
//
@ -1028,6 +1104,48 @@
resources.ApplyResources(this.TabAC2, "TabAC2");
this.TabAC2.Name = "TabAC2";
//
// groupBox17
//
this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX);
this.groupBox17.Controls.Add(this.label27);
this.groupBox17.Controls.Add(this.ACRO_PIT_I);
this.groupBox17.Controls.Add(this.label29);
this.groupBox17.Controls.Add(this.ACRO_PIT_P);
this.groupBox17.Controls.Add(this.label33);
resources.ApplyResources(this.groupBox17, "groupBox17");
this.groupBox17.Name = "groupBox17";
this.groupBox17.TabStop = false;
//
// ACRO_PIT_IMAX
//
resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX");
this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX";
//
// label27
//
resources.ApplyResources(this.label27, "label27");
this.label27.Name = "label27";
//
// ACRO_PIT_I
//
resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I");
this.ACRO_PIT_I.Name = "ACRO_PIT_I";
//
// label29
//
resources.ApplyResources(this.label29, "label29");
this.label29.Name = "label29";
//
// ACRO_PIT_P
//
resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P");
this.ACRO_PIT_P.Name = "ACRO_PIT_P";
//
// label33
//
resources.ApplyResources(this.label33, "label33");
this.label33.Name = "label33";
//
// groupBox5
//
this.groupBox5.Controls.Add(this.label14);
@ -1070,6 +1188,48 @@
resources.ApplyResources(this.label25, "label25");
this.label25.Name = "label25";
//
// groupBox18
//
this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX);
this.groupBox18.Controls.Add(this.label40);
this.groupBox18.Controls.Add(this.ACRO_RLL_I);
this.groupBox18.Controls.Add(this.label44);
this.groupBox18.Controls.Add(this.ACRO_RLL_P);
this.groupBox18.Controls.Add(this.label48);
resources.ApplyResources(this.groupBox18, "groupBox18");
this.groupBox18.Name = "groupBox18";
this.groupBox18.TabStop = false;
//
// ACRO_RLL_IMAX
//
resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX");
this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX";
//
// label40
//
resources.ApplyResources(this.label40, "label40");
this.label40.Name = "label40";
//
// ACRO_RLL_I
//
resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I");
this.ACRO_RLL_I.Name = "ACRO_RLL_I";
//
// label44
//
resources.ApplyResources(this.label44, "label44");
this.label44.Name = "label44";
//
// ACRO_RLL_P
//
resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P");
this.ACRO_RLL_P.Name = "ACRO_RLL_P";
//
// label48
//
resources.ApplyResources(this.label48, "label48");
this.label48.Name = "label48";
//
// CHK_lockrollpitch
//
resources.ApplyResources(this.CHK_lockrollpitch, "CHK_lockrollpitch");
@ -1135,52 +1295,16 @@
//
// groupBox6
//
this.groupBox6.Controls.Add(this.XTRK_ANGLE_CD1);
this.groupBox6.Controls.Add(this.label10);
this.groupBox6.Controls.Add(this.XTRACK_IMAX);
this.groupBox6.Controls.Add(this.label11);
this.groupBox6.Controls.Add(this.XTRACK_I);
this.groupBox6.Controls.Add(this.label17);
this.groupBox6.Controls.Add(this.XTRACK_P);
this.groupBox6.Controls.Add(this.XTRK_GAIN_SC1);
this.groupBox6.Controls.Add(this.label18);
resources.ApplyResources(this.groupBox6, "groupBox6");
this.groupBox6.Name = "groupBox6";
this.groupBox6.TabStop = false;
//
// XTRK_ANGLE_CD1
// XTRK_GAIN_SC1
//
resources.ApplyResources(this.XTRK_ANGLE_CD1, "XTRK_ANGLE_CD1");
this.XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD1";
//
// label10
//
resources.ApplyResources(this.label10, "label10");
this.label10.Name = "label10";
//
// XTRACK_IMAX
//
resources.ApplyResources(this.XTRACK_IMAX, "XTRACK_IMAX");
this.XTRACK_IMAX.Name = "XTRACK_IMAX";
//
// label11
//
resources.ApplyResources(this.label11, "label11");
this.label11.Name = "label11";
//
// XTRACK_I
//
resources.ApplyResources(this.XTRACK_I, "XTRACK_I");
this.XTRACK_I.Name = "XTRACK_I";
//
// label17
//
resources.ApplyResources(this.label17, "label17");
this.label17.Name = "label17";
//
// XTRACK_P
//
resources.ApplyResources(this.XTRACK_P, "XTRACK_P");
this.XTRACK_P.Name = "XTRACK_P";
resources.ApplyResources(this.XTRK_GAIN_SC1, "XTRK_GAIN_SC1");
this.XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC1";
//
// label18
//
@ -1942,90 +2066,6 @@
this.BUT_compare.UseVisualStyleBackColor = true;
this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click);
//
// groupBox17
//
this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX);
this.groupBox17.Controls.Add(this.label27);
this.groupBox17.Controls.Add(this.ACRO_PIT_I);
this.groupBox17.Controls.Add(this.label29);
this.groupBox17.Controls.Add(this.ACRO_PIT_P);
this.groupBox17.Controls.Add(this.label33);
resources.ApplyResources(this.groupBox17, "groupBox17");
this.groupBox17.Name = "groupBox17";
this.groupBox17.TabStop = false;
//
// ACRO_PIT_IMAX
//
resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX");
this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX";
//
// label27
//
resources.ApplyResources(this.label27, "label27");
this.label27.Name = "label27";
//
// ACRO_PIT_I
//
resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I");
this.ACRO_PIT_I.Name = "ACRO_PIT_I";
//
// label29
//
resources.ApplyResources(this.label29, "label29");
this.label29.Name = "label29";
//
// ACRO_PIT_P
//
resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P");
this.ACRO_PIT_P.Name = "ACRO_PIT_P";
//
// label33
//
resources.ApplyResources(this.label33, "label33");
this.label33.Name = "label33";
//
// groupBox18
//
this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX);
this.groupBox18.Controls.Add(this.label40);
this.groupBox18.Controls.Add(this.ACRO_RLL_I);
this.groupBox18.Controls.Add(this.label44);
this.groupBox18.Controls.Add(this.ACRO_RLL_P);
this.groupBox18.Controls.Add(this.label48);
resources.ApplyResources(this.groupBox18, "groupBox18");
this.groupBox18.Name = "groupBox18";
this.groupBox18.TabStop = false;
//
// ACRO_RLL_IMAX
//
resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX");
this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX";
//
// label40
//
resources.ApplyResources(this.label40, "label40");
this.label40.Name = "label40";
//
// ACRO_RLL_I
//
resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I");
this.ACRO_RLL_I.Name = "ACRO_RLL_I";
//
// label44
//
resources.ApplyResources(this.label44, "label44");
this.label44.Name = "label44";
//
// ACRO_RLL_P
//
resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P");
this.ACRO_RLL_P.Name = "ACRO_RLL_P";
//
// label48
//
resources.ApplyResources(this.label48, "label48");
this.label48.Name = "label48";
//
// Configuration
//
resources.ApplyResources(this, "$this");
@ -2044,34 +2084,116 @@
this.ConfigTabs.ResumeLayout(false);
this.TabAPM2.ResumeLayout(false);
this.groupBox3.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).EndInit();
this.groupBox1.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).EndInit();
this.groupBox2.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).EndInit();
this.groupBox15.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).EndInit();
this.groupBox16.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).EndInit();
this.groupBox14.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).EndInit();
this.groupBox13.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).EndInit();
this.groupBox12.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).EndInit();
this.groupBox11.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).EndInit();
this.groupBox10.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).EndInit();
this.groupBox9.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).EndInit();
this.groupBox8.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).EndInit();
this.TabAC2.ResumeLayout(false);
this.TabAC2.PerformLayout();
this.groupBox17.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_PIT_P)).EndInit();
this.groupBox5.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).EndInit();
this.groupBox18.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.ACRO_RLL_P)).EndInit();
this.groupBox4.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).EndInit();
this.groupBox6.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC1)).EndInit();
this.groupBox7.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).EndInit();
this.groupBox19.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).EndInit();
this.groupBox20.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).EndInit();
this.groupBox21.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).EndInit();
this.groupBox22.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).EndInit();
this.groupBox23.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).EndInit();
this.groupBox24.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).EndInit();
this.groupBox25.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).EndInit();
this.TabPlanner.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit();
this.groupBox17.ResumeLayout(false);
this.groupBox18.ResumeLayout(false);
this.ResumeLayout(false);
}
@ -2193,11 +2315,7 @@
private System.Windows.Forms.NumericUpDown NAV_LAT_P;
private System.Windows.Forms.Label label16;
private System.Windows.Forms.GroupBox groupBox6;
private System.Windows.Forms.NumericUpDown XTRACK_IMAX;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.NumericUpDown XTRACK_I;
private System.Windows.Forms.Label label17;
private System.Windows.Forms.NumericUpDown XTRACK_P;
private System.Windows.Forms.NumericUpDown XTRK_GAIN_SC1;
private System.Windows.Forms.Label label18;
private System.Windows.Forms.GroupBox groupBox7;
private System.Windows.Forms.NumericUpDown THR_ALT_IMAX;
@ -2295,8 +2413,6 @@
private System.Windows.Forms.CheckBox CHK_lockrollpitch;
private System.Windows.Forms.NumericUpDown WP_SPEED_MAX;
private System.Windows.Forms.Label label9;
private System.Windows.Forms.NumericUpDown XTRK_ANGLE_CD1;
private System.Windows.Forms.Label label10;
private System.Windows.Forms.CheckBox CHK_speechaltwarning;
private System.Windows.Forms.ToolTip toolTip1;
private System.Windows.Forms.Label label23;

View File

@ -65,7 +65,8 @@ namespace ArdupilotMega.GCSViews
//this.Height = this.Parent.Height;
// fix for dup name
XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD";
//XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD";
XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC";
}
private void Configuration_Load(object sender, EventArgs e)
@ -231,6 +232,9 @@ namespace ArdupilotMega.GCSViews
string data = resources.GetString("MAVParam");
if (data == null)
return;
string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
foreach (var tip in tips)
@ -290,11 +294,29 @@ namespace ArdupilotMega.GCSViews
return sb.ToString();
}
void disableNumericUpDownControls(Control inctl)
{
foreach (Control ctl in inctl.Controls)
{
if (ctl.Controls.Count > 0)
{
disableNumericUpDownControls(ctl);
}
if (ctl.GetType() == typeof(NumericUpDown))
{
ctl.Enabled = false;
}
}
}
internal void processToScreen()
{
toolTip1.RemoveAll();
Params.Rows.Clear();
disableNumericUpDownControls(TabAC2);
disableNumericUpDownControls(TabAPM2);
// process hashdefines and update display
foreach (string value in param.Keys)
{
@ -342,6 +364,8 @@ namespace ArdupilotMega.GCSViews
thisctl.DecimalPlaces = 1;
}
thisctl.Enabled = true;
thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
thisctl.Validated += null;
if (tooltips[value] != null)

File diff suppressed because it is too large Load Diff

View File

@ -268,6 +268,7 @@ namespace ArdupilotMega.GCSViews
{
public string url;
public string url2560;
public string url2560_2;
public string name;
public string desc;
public int k_format_version;
@ -295,6 +296,7 @@ namespace ArdupilotMega.GCSViews
{
string url = "";
string url2560 = "";
string url2560_2 = "";
string name = "";
string desc = "";
int k_format_version = 0;
@ -317,6 +319,9 @@ namespace ArdupilotMega.GCSViews
case "url2560":
url2560 = xmlreader.ReadString();
break;
case "url2560-2":
url2560_2 = xmlreader.ReadString();
break;
case "name":
name = xmlreader.ReadString();
break;
@ -333,6 +338,7 @@ namespace ArdupilotMega.GCSViews
temp.name = name;
temp.url = url;
temp.url2560 = url2560;
temp.url2560_2 = url2560_2;
temp.k_format_version = k_format_version;
try
@ -518,6 +524,10 @@ namespace ArdupilotMega.GCSViews
{
baseurl = temp.url.ToString();
}
else if (board == "2560-2")
{
baseurl = temp.url2560_2.ToString();
}
else
{
MessageBox.Show("Invalid Board Type");

View File

@ -272,11 +272,6 @@ namespace ArdupilotMega.GCSViews
cell.Value = lng.ToString("0.0000000");
cell.DataGridView.EndEdit();
}
if (Commands.Columns[Param1.Index].HeaderText.Equals(cmdParamNames["WAYPOINT"][0]/*"Delay"*/))
{
cell = Commands.Rows[selectedrow].Cells[Param1.Index] as DataGridViewTextBoxCell;
cell.Value = 0;
}
if (alt != -1 && Commands.Columns[Alt.Index].HeaderText.Equals(cmdParamNames["WAYPOINT"][6]/*"Alt"*/))
{
cell = Commands.Rows[selectedrow].Cells[Alt.Index] as DataGridViewTextBoxCell;
@ -628,6 +623,9 @@ namespace ArdupilotMega.GCSViews
quickadd = false;
if (MainV2.config["WMSserver"] != null)
MainMap.Manager.CustomWMSURL = MainV2.config["WMSserver"].ToString();
trackBar1.Value = (int)MainMap.Zoom;
// check for net and set offline if needed
@ -696,7 +694,8 @@ namespace ArdupilotMega.GCSViews
DataGridViewCell tcell = Commands.Rows[e.RowIndex].Cells[i];
if (tcell.GetType() == typeof(DataGridViewTextBoxCell))
{
tcell.Value = "0";
if (tcell.Value == null)
tcell.Value = "0";
}
}
@ -1339,10 +1338,8 @@ namespace ArdupilotMega.GCSViews
}
int alt = (int)temp.alt;
cell = Commands.Rows[i].Cells[Alt.Index] as DataGridViewTextBoxCell;
cell.Value = (int)((double)alt * MainV2.cs.multiplierdist);
cell.Value = Math.Round((temp.alt * MainV2.cs.multiplierdist), 0);
cell = Commands.Rows[i].Cells[Lat.Index] as DataGridViewTextBoxCell;
cell.Value = (double)temp.lat;
cell = Commands.Rows[i].Cells[Lon.Index] as DataGridViewTextBoxCell;
@ -1784,6 +1781,15 @@ namespace ArdupilotMega.GCSViews
MainMap.ZoomAndCenterMarkers("objects");
if (type == MapType.CustomWMS)
{
string url = "";
if (MainV2.config["WMSserver"] != null)
url = MainV2.config["WMSserver"].ToString();
Common.InputBox("WMS Server", "Enter the WMS server URL", ref url);
MainV2.config["WMSserver"] = url;
MainMap.Manager.CustomWMSURL = url;
}
}
void MainMap_MouseUp(object sender, MouseEventArgs e)
@ -2632,7 +2638,7 @@ namespace ArdupilotMega.GCSViews
{
selectedrow = Commands.Rows.Add();
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_UNLIM;
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_UNLIM.ToString();
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
}
@ -2644,7 +2650,7 @@ namespace ArdupilotMega.GCSViews
int row = Commands.Rows.Add();
Commands.Rows[row].Cells[Command.Index].Value = MAVLink.MAV_CMD.DO_JUMP;
Commands.Rows[row].Cells[Command.Index].Value = MAVLink.MAV_CMD.DO_JUMP.ToString();
Commands.Rows[row].Cells[Param1.Index].Value = 1;
@ -2660,7 +2666,7 @@ namespace ArdupilotMega.GCSViews
int row = Commands.Rows.Add();
Commands.Rows[row].Cells[Command.Index].Value = MAVLink.MAV_CMD.DO_JUMP;
Commands.Rows[row].Cells[Command.Index].Value = MAVLink.MAV_CMD.DO_JUMP.ToString();
Commands.Rows[row].Cells[Param1.Index].Value = wp;
@ -2707,7 +2713,7 @@ namespace ArdupilotMega.GCSViews
selectedrow = Commands.Rows.Add();
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_TIME;
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_TIME.ToString();
Commands.Rows[selectedrow].Cells[Param1.Index].Value = time;
@ -2721,7 +2727,7 @@ namespace ArdupilotMega.GCSViews
selectedrow = Commands.Rows.Add();
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_TURNS;
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_TURNS.ToString();
Commands.Rows[selectedrow].Cells[Param1.Index].Value = turns;

View File

@ -172,13 +172,6 @@ namespace ArdupilotMega.GCSViews
comPort.Open();
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
System.Threading.Thread t11 = new System.Threading.Thread(delegate()
{
threadrun = true;

View File

@ -1,6 +1,5 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using YLScsDrawing.Drawing3d;

View File

@ -149,8 +149,8 @@ namespace ArdupilotMega.HIL
Random rand = new Random();
int fixme;
//velocity.X += .05 + rand.NextDouble() * .03;
//velocity.Y += .05 + rand.NextDouble() * .03;
//velocity.X += .02 + rand.NextDouble() * .03;
//velocity.Y += .02 + rand.NextDouble() * .03;
//# new velocity vector
velocity += accel3D * delta_time.TotalSeconds;

View File

@ -14,6 +14,7 @@ namespace ArdupilotMega
{
public partial class MAVLink
{
public ICommsSerial BaseStream = new SerialPort();
/// <summary>
@ -624,8 +625,9 @@ namespace ArdupilotMega
}
if (!(restart.AddMilliseconds(1000) > DateTime.Now))
{
rereq.param_id = new byte[] {0x0,0x0};
rereq.param_index = (short)nextid;
generatePacket(MAVLINK_MSG_ID_PARAM_REQUEST_READ, rereq);
sendPacket(rereq);
restart = DateTime.Now;
}
@ -736,10 +738,7 @@ namespace ArdupilotMega
// reset all
if (forget)
{
lock (objlock)
{
streams = new byte[streams.Length];
}
}
// no error on bad
@ -1010,10 +1009,7 @@ namespace ArdupilotMega
public void requestDatastream(byte id, byte hzrate)
{
lock (objlock)
{
streams[id] = hzrate;
}
double pps = 0;
@ -2087,6 +2083,7 @@ namespace ArdupilotMega
if (temp.Length >= 5 && temp[3] == 255 && logreadmode) // gcs packet
{
getWPsfromstream(ref temp);
return temp;// new byte[0];
}
@ -2163,53 +2160,20 @@ namespace ArdupilotMega
if (temp[5] == MAVLink.MAVLINK_MSG_ID_STATUSTEXT) // status text
{
string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(temp, 6, temp.Length - 6);
string logdata = Encoding.ASCII.GetString(temp, 7, temp.Length - 7);
int ind = logdata.IndexOf('\0');
if (ind != -1)
logdata = logdata.Substring(0, ind);
Console.WriteLine(logdata);
}
#if MAVLINK10
if (temp[5] == MAVLINK_MSG_ID_MISSION_COUNT)
{
// clear old
wps = new PointLatLngAlt[wps.Length];
Console.WriteLine(DateTime.Now + " " + logdata);
if (MainV2.talk != null && MainV2.config["speechenable"] != null && MainV2.config["speechenable"].ToString() == "True")
{
MainV2.talk.SpeakAsync(logdata);
}
}
if (temp[5] == MAVLink.MAVLINK_MSG_ID_MISSION_ITEM)
{
__mavlink_mission_item_t wp = new __mavlink_mission_item_t();
object structtemp = (object)wp;
//Array.Copy(buffer, 6, buffer, 0, buffer.Length - 6);
ByteArrayToStructure(temp, ref structtemp, 6);
wp = (__mavlink_mission_item_t)(structtemp);
#else
if (temp[5] == MAVLINK_MSG_ID_WAYPOINT_COUNT)
{
// clear old
wps = new PointLatLngAlt[wps.Length];
}
if (temp[5] == MAVLink.MAVLINK_MSG_ID_WAYPOINT)
{
__mavlink_waypoint_t wp = new __mavlink_waypoint_t();
object structtemp = (object)wp;
//Array.Copy(buffer, 6, buffer, 0, buffer.Length - 6);
ByteArrayToStructure(temp, ref structtemp, 6);
wp = (__mavlink_waypoint_t)(structtemp);
#endif
wps[wp.seq] = new PointLatLngAlt(wp.x, wp.y, wp.z, wp.seq.ToString());
}
getWPsfromstream(ref temp);
try
{
@ -2237,6 +2201,55 @@ namespace ArdupilotMega
return temp;
}
/// <summary>
/// Used to extract mission from log file
/// </summary>
/// <param name="temp">packet</param>
void getWPsfromstream(ref byte[] temp )
{
#if MAVLINK10
if (temp[5] == MAVLINK_MSG_ID_MISSION_COUNT)
{
// clear old
wps = new PointLatLngAlt[wps.Length];
}
if (temp[5] == MAVLink.MAVLINK_MSG_ID_MISSION_ITEM)
{
__mavlink_mission_item_t wp = new __mavlink_mission_item_t();
object structtemp = (object)wp;
//Array.Copy(buffer, 6, buffer, 0, buffer.Length - 6);
ByteArrayToStructure(temp, ref structtemp, 6);
wp = (__mavlink_mission_item_t)(structtemp);
#else
if (temp[5] == MAVLINK_MSG_ID_WAYPOINT_COUNT)
{
// clear old
wps = new PointLatLngAlt[wps.Length];
}
if (temp[5] == MAVLink.MAVLINK_MSG_ID_WAYPOINT)
{
__mavlink_waypoint_t wp = new __mavlink_waypoint_t();
object structtemp = (object)wp;
//Array.Copy(buffer, 6, buffer, 0, buffer.Length - 6);
ByteArrayToStructure(temp, ref structtemp, 6);
wp = (__mavlink_waypoint_t)(structtemp);
#endif
wps[wp.seq] = new PointLatLngAlt(wp.x, wp.y, wp.z, wp.seq.ToString());
}
}
byte[] readlogPacket()
{
byte[] temp = new byte[300];

View File

@ -21,6 +21,7 @@ using System.Threading;
using System.Net.Sockets;
using IronPython.Hosting;
namespace ArdupilotMega
{
public partial class MainV2 : Form
@ -86,6 +87,17 @@ namespace ArdupilotMega
public MainV2()
{
Form splash = new Splash();
splash.Show();
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
strVersion = "";
splash.Text = "APM Planner " + Application.ProductVersion + " " + strVersion + " By Michael Oborne";
splash.Refresh();
Application.DoEvents();
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
@ -109,17 +121,6 @@ namespace ArdupilotMega
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
Form splash = new Splash();
splash.Show();
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
strVersion = "";
splash.Text = "APM Planner " + Application.ProductVersion + " " + strVersion + " By Michael Oborne";
splash.Refresh();
Application.DoEvents();
//talk.SpeakAsync("Welcome to APM Planner");
InitializeComponent();
@ -767,6 +768,7 @@ namespace ArdupilotMega
else
{
CMB_baudrate.Enabled = true;
MainV2.comPort.BaseStream = new ArdupilotMega.SerialPort();
}
try
@ -774,7 +776,13 @@ namespace ArdupilotMega
comPort.BaseStream.PortName = CMB_serialport.Text;
if (config[CMB_serialport.Text + "_BAUD"] != null)
{
CMB_baudrate.Text = config[CMB_serialport.Text + "_BAUD"].ToString();
}
else
{
MainV2.comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
}
}
catch { }
}
@ -1449,6 +1457,17 @@ namespace ArdupilotMega
}
catch (Exception ex) { MessageBox.Show("Update Failed " + ex.Message); }
}
private static void updatelabel(Label loadinglabel,string text)
{
MainV2.instance.Invoke((MethodInvoker)delegate
{
loadinglabel.Text = text;
});
Application.DoEvents();
}
private static bool updatecheck(Label loadinglabel, string baseurl, string subdir)
{
bool update = false;
@ -1508,7 +1527,7 @@ namespace ArdupilotMega
continue;
}
if (loadinglabel != null)
loadinglabel.Text = "Checking " + file;
updatelabel(loadinglabel, "Checking " + file);
string path = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + subdir + file;
@ -1572,7 +1591,7 @@ namespace ArdupilotMega
}
}
if (loadinglabel != null)
loadinglabel.Text = "Getting " + file;
updatelabel(loadinglabel,"Getting " + file);
// Create a request using a URL that can receive a post.
request = WebRequest.Create(baseurl + file);
@ -1604,7 +1623,7 @@ namespace ArdupilotMega
if (dt.Second != DateTime.Now.Second)
{
if (loadinglabel != null)
loadinglabel.Text = "Getting " + file + ": " + Math.Abs(bytes) + " bytes";//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
updatelabel(loadinglabel,"Getting " + file + ": " + Math.Abs(bytes) + " bytes");//(((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%";
dt = DateTime.Now;
}
}

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.0.96")]
[assembly: AssemblyFileVersion("1.0.98")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -0,0 +1,162 @@
namespace resedit
{
partial class Form1
{
/// <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 Windows Form 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()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Form1));
this.dataGridView1 = new System.Windows.Forms.DataGridView();
this.colFile = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colInternal = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colEnglish = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.colOtherLang = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.button2 = new System.Windows.Forms.Button();
this.comboBox1 = new System.Windows.Forms.ComboBox();
this.richTextBox1 = new System.Windows.Forms.RichTextBox();
this.button3 = new System.Windows.Forms.Button();
((System.ComponentModel.ISupportInitialize)(this.dataGridView1)).BeginInit();
this.SuspendLayout();
//
// dataGridView1
//
this.dataGridView1.AllowUserToAddRows = false;
this.dataGridView1.AllowUserToDeleteRows = false;
this.dataGridView1.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
| System.Windows.Forms.AnchorStyles.Left)
| System.Windows.Forms.AnchorStyles.Right)));
this.dataGridView1.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
this.dataGridView1.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.colFile,
this.colInternal,
this.colEnglish,
this.colOtherLang});
this.dataGridView1.Location = new System.Drawing.Point(12, 80);
this.dataGridView1.Name = "dataGridView1";
this.dataGridView1.Size = new System.Drawing.Size(844, 370);
this.dataGridView1.TabIndex = 0;
//
// colFile
//
this.colFile.HeaderText = "File";
this.colFile.Name = "colFile";
this.colFile.ReadOnly = true;
//
// colInternal
//
this.colInternal.HeaderText = "Internal";
this.colInternal.Name = "colInternal";
this.colInternal.ReadOnly = true;
this.colInternal.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
this.colInternal.Width = 150;
//
// colEnglish
//
this.colEnglish.HeaderText = "English";
this.colEnglish.Name = "colEnglish";
this.colEnglish.ReadOnly = true;
this.colEnglish.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
this.colEnglish.Width = 150;
//
// colOtherLang
//
this.colOtherLang.HeaderText = "Other Lang";
this.colOtherLang.Name = "colOtherLang";
this.colOtherLang.SortMode = System.Windows.Forms.DataGridViewColumnSortMode.NotSortable;
this.colOtherLang.Width = 150;
//
// button2
//
this.button2.Anchor = System.Windows.Forms.AnchorStyles.Bottom;
this.button2.Location = new System.Drawing.Point(578, 457);
this.button2.Name = "button2";
this.button2.Size = new System.Drawing.Size(75, 23);
this.button2.TabIndex = 2;
this.button2.Text = "Save";
this.button2.UseVisualStyleBackColor = true;
this.button2.Click += new System.EventHandler(this.button2_Click);
//
// comboBox1
//
this.comboBox1.Anchor = System.Windows.Forms.AnchorStyles.Bottom;
this.comboBox1.FormattingEnabled = true;
this.comboBox1.Location = new System.Drawing.Point(298, 459);
this.comboBox1.Name = "comboBox1";
this.comboBox1.Size = new System.Drawing.Size(274, 21);
this.comboBox1.TabIndex = 3;
this.comboBox1.SelectedIndexChanged += new System.EventHandler(this.comboBox1_SelectedIndexChanged);
//
// richTextBox1
//
this.richTextBox1.Location = new System.Drawing.Point(12, 13);
this.richTextBox1.Name = "richTextBox1";
this.richTextBox1.Size = new System.Drawing.Size(844, 61);
this.richTextBox1.TabIndex = 4;
this.richTextBox1.Text = resources.GetString("richTextBox1.Text");
//
// button3
//
this.button3.Anchor = System.Windows.Forms.AnchorStyles.Bottom;
this.button3.Location = new System.Drawing.Point(781, 457);
this.button3.Name = "button3";
this.button3.Size = new System.Drawing.Size(75, 23);
this.button3.TabIndex = 5;
this.button3.Text = "Extra";
this.button3.UseVisualStyleBackColor = true;
this.button3.Click += new System.EventHandler(this.button3_Click);
//
// Form1
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(868, 484);
this.Controls.Add(this.button3);
this.Controls.Add(this.richTextBox1);
this.Controls.Add(this.comboBox1);
this.Controls.Add(this.button2);
this.Controls.Add(this.dataGridView1);
this.Name = "Form1";
this.Text = "Language Editor";
this.Load += new System.EventHandler(this.Form1_Load);
((System.ComponentModel.ISupportInitialize)(this.dataGridView1)).EndInit();
this.ResumeLayout(false);
}
#endregion
private System.Windows.Forms.DataGridView dataGridView1;
private System.Windows.Forms.Button button2;
private System.Windows.Forms.ComboBox comboBox1;
private System.Windows.Forms.RichTextBox richTextBox1;
private System.Windows.Forms.DataGridViewTextBoxColumn colFile;
private System.Windows.Forms.DataGridViewTextBoxColumn colInternal;
private System.Windows.Forms.DataGridViewTextBoxColumn colEnglish;
private System.Windows.Forms.DataGridViewTextBoxColumn colOtherLang;
private System.Windows.Forms.Button button3;
}
}

View File

@ -0,0 +1,284 @@
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Data;
using System.Drawing;
using System.Linq;
using System.Text;
using System.Windows.Forms;
using System.Resources;
using System.Collections;
using System.Globalization;
using System.IO;
using System.Net;
using System.Text.RegularExpressions;
using System.Reflection;
using System.Xml;
namespace resedit
{
public partial class Form1 : Form
{
public Form1()
{
InitializeComponent();
List<string> list = new List<string>();
list.Add("");
CultureInfo[] temp = System.Globalization.CultureInfo.GetCultures(CultureTypes.AllCultures);
foreach (CultureInfo cul in temp)
{
list.Add(cul.DisplayName + " " + cul.Name);
}
list.Sort();
comboBox1.DataSource = list;
}
private void Form1_Load(object sender, EventArgs e)
{
Assembly thisAssembly = Assembly.GetExecutingAssembly();
string[] test = Assembly.GetExecutingAssembly().GetManifestResourceNames();
foreach (string file in test)
{
Stream rgbxml = thisAssembly.GetManifestResourceStream(
file);
try
{
ResourceReader res = new ResourceReader(rgbxml);
IDictionaryEnumerator dict = res.GetEnumerator();
while (dict.MoveNext())
{
Console.WriteLine(" {0}: '{1}' (Type {2})",
dict.Key, dict.Value, dict.Value.GetType().Name);
if (dict.Key.ToString().EndsWith(".ToolTip") || dict.Key.ToString().EndsWith(".Text") || dict.Key.ToString().EndsWith("HeaderText") || dict.Key.ToString().EndsWith("ToolTipText"))
{
dataGridView1.Rows.Add();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colFile.Index].Value = System.IO.Path.GetFileName(file);
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colInternal.Index].Value = dict.Key.ToString();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colEnglish.Index].Value = dict.Value.ToString();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colOtherLang.Index].Value = dict.Value.ToString();
}
}
} catch {}
}
}
private void button1_Click(object sender, EventArgs e)
{
FolderBrowserDialog fbd = new FolderBrowserDialog();
fbd.SelectedPath = System.IO.Path.GetDirectoryName(Application.ExecutablePath);
fbd.ShowDialog();
if (fbd.SelectedPath != "")
{
dataGridView1.Rows.Clear();
string[] files = System.IO.Directory.GetFiles(fbd.SelectedPath, "*.resx", System.IO.SearchOption.AllDirectories);
string ci = "";
CultureInfo[] temp = System.Globalization.CultureInfo.GetCultures(CultureTypes.AllCultures);
foreach (CultureInfo cul in temp)
{
if ((cul.DisplayName + " " + cul.Name) == comboBox1.Text)
{
Console.WriteLine(cul.Name);
ci = cul.Name;
}
}
foreach (string file in files)
{
// load only file of the slected lang
if (!file.ToLower().Contains(ci.ToString().ToLower() + ".resx"))
continue;
// dont load and tralations if no lang selected
if (file.ToLower().Contains("translation") && comboBox1.Text == "")
continue;
// must be a resx
if (!file.ToLower().EndsWith(".resx"))
continue;
ResXResourceReader reader = new ResXResourceReader(file);
Console.WriteLine(reader);
reader.BasePath = fbd.SelectedPath + System.IO.Path.DirectorySeparatorChar +"Resources";
try
{
foreach (DictionaryEntry entry in reader)
{
if (entry.Key.ToString().EndsWith(".ToolTip") || entry.Key.ToString().EndsWith(".Text") || entry.Key.ToString().EndsWith("HeaderText") || entry.Key.ToString().EndsWith("ToolTipText"))
{
dataGridView1.Rows.Add();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colFile.Index].Value = System.IO.Path.GetFileName(file);
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colInternal.Index].Value = entry.Key.ToString();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colEnglish.Index].Value = entry.Value.ToString();
dataGridView1.Rows[dataGridView1.RowCount - 1].Cells[colOtherLang.Index].Value = entry.Value.ToString();
}
}
}
catch (Exception ex) { Console.WriteLine(ex.ToString()); }
}
}
}
private void button2_Click(object sender, EventArgs e)
{
string ci = "";
CultureInfo[] temp = System.Globalization.CultureInfo.GetCultures(CultureTypes.AllCultures);
foreach (CultureInfo cul in temp)
{
if ((cul.DisplayName + " " + cul.Name) == comboBox1.Text)
{
Console.WriteLine(cul.Name);
ci = cul.Name;
}
}
string fname = "";
ResXResourceWriter writer = null;
System.IO.Directory.CreateDirectory("translation");
StreamWriter sw = new StreamWriter("translation/output.html");
sw.Write("<html><body><table>");
foreach (DataGridViewRow row in dataGridView1.Rows)
{
try
{
if (row.Cells[colFile.Index].Value.ToString() != fname)
{
if (writer != null)
writer.Close();
writer = new ResXResourceWriter("translation/" + row.Cells[colFile.Index].Value.ToString().Replace(".resx", "." + ci + ".resx"));
}
writer.AddResource(row.Cells[colInternal.Index].Value.ToString(), row.Cells[colOtherLang.Index].Value.ToString());
fname = row.Cells[colFile.Index].Value.ToString();
}
catch { }
try
{
sw.Write("<tr><td>" + row.Cells[colFile.Index].Value.ToString() + "</td><td>" + row.Cells[colInternal.Index].Value.ToString() + "</td><td>" + row.Cells[colOtherLang.Index].Value.ToString() + "</td></tr>");
}
catch (Exception ex) { try { MessageBox.Show("Failed to save " + row.Cells[colOtherLang.Index].Value.ToString() + " " + ex.ToString()); } catch { } }
}
if (writer != null)
writer.Close();
sw.Write("</table></html>");
sw.Close();
}
private void button3_Click(object sender, EventArgs e)
{
StreamReader sr1 = new StreamReader("translation/output.txt");
StreamReader sr2 = new StreamReader("translation/output.ru.txt", Encoding.Unicode);
while (!sr1.EndOfStream)
{
string line1 = sr1.ReadLine();
string line1a = sr2.ReadLine();
int index1 = line1.IndexOf(' ', line1.IndexOf(' ') + 1) + 1;
int index1a = line1a.IndexOf(' ',line1a.IndexOf(' ')+1)+1;
foreach (DataGridViewRow row in dataGridView1.Rows)
{
if (line1.Contains(row.Cells[colFile.Index].Value.ToString()) && line1.Contains(row.Cells[colInternal.Index].Value.ToString()))
{
row.Cells[colOtherLang.Index].Value = line1a.Substring(index1a);
}
}
}
sr1.Close();
sr2.Close();
}
private void comboBox1_SelectedIndexChanged(object sender, EventArgs e)
{
string ci = "";
CultureInfo[] temp = System.Globalization.CultureInfo.GetCultures(CultureTypes.AllCultures);
foreach (CultureInfo cul in temp)
{
if ((cul.DisplayName + " " + cul.Name) == comboBox1.Text)
{
Console.WriteLine(cul.Name);
ci = cul.Name;
}
}
Assembly thisAssembly;
try
{
thisAssembly = Assembly.LoadFile(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + ci + Path.DirectorySeparatorChar + "ArdupilotMegaPlanner.resources.dll");
}
catch { return; }
string[] test = thisAssembly.GetManifestResourceNames();
Encoding unicode = Encoding.Unicode;
foreach (string file in test)
{
Stream rgbxml = thisAssembly.GetManifestResourceStream(
file);
try
{
ResourceReader res = new ResourceReader(rgbxml);
IDictionaryEnumerator dict = res.GetEnumerator();
while (dict.MoveNext())
{
Console.WriteLine(" {0}: '{1}' (Type {2})",
dict.Key, dict.Value, dict.Value.GetType().Name);
string thing = (string)dict.Value;
// dataGridView1.Rows[0].Cells[colOtherLang.Index].Value = dict.Value.ToString();
foreach (DataGridViewRow row in dataGridView1.Rows)
{
string t2 = file.Replace(ci + ".", "");
if (row.Cells[0].Value.ToString() == t2 && row.Cells[1].Value.ToString() == dict.Key.ToString())
{
row.Cells[3].Value = thing;
}
}
}
}
catch { }
}
}
}
}

View File

@ -1,174 +1,154 @@
<?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>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="glControl1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="glControl1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
</data>
<data name="glControl1.Size" type="System.Drawing.Size, System.Drawing">
<value>300, 225</value>
</data>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="glControl1.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="&gt;&gt;glControl1.Name" xml:space="preserve">
<value>glControl1</value>
</data>
<data name="&gt;&gt;glControl1.Type" xml:space="preserve">
<value>OpenTK.GLControl, OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4</value>
</data>
<data name="&gt;&gt;glControl1.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;glControl1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="$this.Localizable" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="$this.Size" type="System.Drawing.Size, System.Drawing">
<value>300, 225</value>
</data>
<data name="&gt;&gt;$this.Name" xml:space="preserve">
<value>HUD</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="Bat" xml:space="preserve">
<value>Bat</value>
</data>
<data name="GPS: 2D Fix.Text" xml:space="preserve">
<value>GPS: 3D Fix</value>
</data>
<data name="GPS: 3D Fix.Text" xml:space="preserve">
<value>GPS: 3D Fix</value>
</data>
<data name="GPS: No Fix.Text" xml:space="preserve">
<value>GPS: No Fix</value>
</data>
<data name="GPS: No GPS.Text" xml:space="preserve">
<value>GPS: No GPS</value>
</data>
<?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="colFile.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colInternal.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colEnglish.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colOtherLang.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colFile.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colInternal.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colEnglish.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<metadata name="colOtherLang.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="richTextBox1.Text" xml:space="preserve">
<value>How to use:
First time
if this is the first load, simple click load (ensure box next to it is blank)
before you save ensure you pick your language and click save.
More uses
Pick your language and click load.
before you save ensure you pick your language and click save.
</value>
</data>
</root>

View File

@ -8,14 +8,62 @@ namespace ArdupilotMega
public class Script
{
DateTime timeout = DateTime.Now;
List<string> items = new List<string>();
// keeps history
MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
public Script()
{
object thisBoxed = MainV2.cs;
Type test = thisBoxed.GetType();
foreach (var field in test.GetProperties())
{
// field.Name has the field's name.
object fieldValue;
try
{
fieldValue = field.GetValue(thisBoxed, null); // Get value
}
catch { continue; }
// Get the TypeCode enumeration. Multiple types get mapped to a common typecode.
TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType());
items.Add(field.Name);
}
}
public enum Conditional
{
LT = 0,
NONE = 0,
LT,
LTEQ,
EQ,
GT,
GTEQ
GTEQ,
NEQ
}
public bool ChangeParam(string param, float value)
{
return MainV2.comPort.setParam(param, value);
}
public bool ChangeMode(string mode)
{
MainV2.comPort.setMode(mode);
return true;
}
public bool WaitFor(string message)
{
while (MainV2.cs.message != message) {
System.Threading.Thread.Sleep(5);
}
return true;
}
public bool WaitFor(string item, Conditional cond,double value ,int timeoutms)
@ -32,5 +80,56 @@ namespace ArdupilotMega
return false;
}
public bool sendRC(int channel, ushort pwm)
{
switch (channel)
{
case 1:
MainV2.cs.rcoverridech1 = pwm;
rc.chan1_raw = pwm;
break;
case 2:
MainV2.cs.rcoverridech2 = pwm;
rc.chan2_raw = pwm;
break;
case 3:
MainV2.cs.rcoverridech3 = pwm;
rc.chan3_raw = pwm;
break;
case 4:
MainV2.cs.rcoverridech4 = pwm;
rc.chan4_raw = pwm;
break;
case 5:
MainV2.cs.rcoverridech5 = pwm;
rc.chan5_raw = pwm;
break;
case 6:
MainV2.cs.rcoverridech6 = pwm;
rc.chan6_raw = pwm;
break;
case 7:
MainV2.cs.rcoverridech7 = pwm;
rc.chan7_raw = pwm;
break;
case 8:
MainV2.cs.rcoverridech8 = pwm;
rc.chan8_raw = pwm;
break;
}
MainV2.comPort.sendPacket(rc);
System.Threading.Thread.Sleep(20);
MainV2.comPort.sendPacket(rc);
MainV2.comPort.sendPacket(rc);
return true;
}
void convertItemtoMessage()
{
}
}
}

View File

@ -3,7 +3,6 @@ using System.Collections.Generic;
using System.ComponentModel;
using System.Data;
using System.Drawing;
using System.Linq;
using System.Text;
using System.Windows.Forms;

View File

@ -1,12 +1,11 @@
<?xml version="1.0"?>
<configuration>
<configSections>
</configSections>
<configSections>
</configSections>
<startup>
<supportedRuntime version="v4.0" sku=".NETFramework,Version=v4.0"/></startup>
<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
<supportedRuntime version="v2.0.50727"/>
</startup>
<!--<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
</startup>-->
</configuration>

View File

@ -3,18 +3,15 @@
<assemblyIdentity name="ArdupilotMegaPlanner.application" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" xmlns="urn:schemas-microsoft-com:asm.v1" />
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
<deployment install="true" />
<compatibleFrameworks xmlns="urn:schemas-microsoft-com:clickonce.v2">
<framework targetVersion="4.0" profile="Full" supportedRuntime="4.0.30319" />
</compatibleFrameworks>
<dependency>
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="19987">
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="23309">
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
<hash>
<dsig:Transforms>
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>l2Rn8qTiwOzQt8/BkJyqqyHeXA0=</dsig:DigestValue>
<dsig:DigestValue>XqmS8DEyaXOEHAzbfxq+pbxDUg4=</dsig:DigestValue>
</hash>
</dependentAssembly>
</dependency>

View File

@ -1,12 +1,11 @@
<?xml version="1.0"?>
<configuration>
<configSections>
</configSections>
<configSections>
</configSections>
<startup>
<supportedRuntime version="v4.0" sku=".NETFramework,Version=v4.0"/></startup>
<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
<supportedRuntime version="v2.0.50727"/>
</startup>
<!--<startup useLegacyV2RuntimeActivationPolicy="true">
<supportedRuntime version="v4.0"/>
</startup>-->
</configuration>

View File

@ -1,705 +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>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="pictureBoxAPM.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="pictureBoxAPM.Location" type="System.Drawing.Point, System.Drawing">
<value>45, -9</value>
</data>
<data name="pictureBoxAPM.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxAPM.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="pictureBoxAPM.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="&gt;&gt;pictureBoxAPM.Name" xml:space="preserve">
<value>pictureBoxAPM</value>
</data>
<data name="&gt;&gt;pictureBoxAPM.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxAPM.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxAPM.ZOrder" xml:space="preserve">
<value>19</value>
</data>
<data name="pictureBoxAPMHIL.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxAPMHIL.Location" type="System.Drawing.Point, System.Drawing">
<value>45, 184</value>
</data>
<data name="pictureBoxAPMHIL.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxAPMHIL.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxAPMHIL.TabIndex" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="&gt;&gt;pictureBoxAPMHIL.Name" xml:space="preserve">
<value>pictureBoxAPMHIL</value>
</data>
<data name="&gt;&gt;pictureBoxAPMHIL.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxAPMHIL.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxAPMHIL.ZOrder" xml:space="preserve">
<value>18</value>
</data>
<data name="pictureBoxQuad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxQuad.Location" type="System.Drawing.Point, System.Drawing">
<value>563, -10</value>
</data>
<data name="pictureBoxQuad.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxQuad.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxQuad.TabIndex" type="System.Int32, mscorlib">
<value>2</value>
</data>
<data name="&gt;&gt;pictureBoxQuad.Name" xml:space="preserve">
<value>pictureBoxQuad</value>
</data>
<data name="&gt;&gt;pictureBoxQuad.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxQuad.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxQuad.ZOrder" xml:space="preserve">
<value>17</value>
</data>
<data name="pictureBoxHexa.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxHexa.Location" type="System.Drawing.Point, System.Drawing">
<value>770, -10</value>
</data>
<data name="pictureBoxHexa.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxHexa.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxHexa.TabIndex" type="System.Int32, mscorlib">
<value>3</value>
</data>
<data name="&gt;&gt;pictureBoxHexa.Name" xml:space="preserve">
<value>pictureBoxHexa</value>
</data>
<data name="&gt;&gt;pictureBoxHexa.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxHexa.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxHexa.ZOrder" xml:space="preserve">
<value>16</value>
</data>
<data name="pictureBoxTri.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxTri.Location" type="System.Drawing.Point, System.Drawing">
<value>563, 184</value>
</data>
<data name="pictureBoxTri.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxTri.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxTri.TabIndex" type="System.Int32, mscorlib">
<value>4</value>
</data>
<data name="&gt;&gt;pictureBoxTri.Name" xml:space="preserve">
<value>pictureBoxTri</value>
</data>
<data name="&gt;&gt;pictureBoxTri.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxTri.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxTri.ZOrder" xml:space="preserve">
<value>15</value>
</data>
<data name="pictureBoxY6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxY6.Location" type="System.Drawing.Point, System.Drawing">
<value>770, 184</value>
</data>
<data name="pictureBoxY6.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxY6.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxY6.TabIndex" type="System.Int32, mscorlib">
<value>5</value>
</data>
<data name="&gt;&gt;pictureBoxY6.Name" xml:space="preserve">
<value>pictureBoxY6</value>
</data>
<data name="&gt;&gt;pictureBoxY6.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxY6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxY6.ZOrder" xml:space="preserve">
<value>14</value>
</data>
<data name="lbl_status.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="lbl_status.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_status.Location" type="System.Drawing.Point, System.Drawing">
<value>8, 443</value>
</data>
<data name="lbl_status.Size" type="System.Drawing.Size, System.Drawing">
<value>37, 13</value>
</data>
<data name="lbl_status.TabIndex" type="System.Int32, mscorlib">
<value>7</value>
</data>
<data name="lbl_status.Text" xml:space="preserve">
<value>Status</value>
</data>
<data name="&gt;&gt;lbl_status.Name" xml:space="preserve">
<value>lbl_status</value>
</data>
<data name="&gt;&gt;lbl_status.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_status.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_status.ZOrder" xml:space="preserve">
<value>12</value>
</data>
<data name="progress.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="progress.Location" type="System.Drawing.Point, System.Drawing">
<value>11, 417</value>
</data>
<data name="progress.Size" type="System.Drawing.Size, System.Drawing">
<value>988, 23</value>
</data>
<data name="progress.TabIndex" type="System.Int32, mscorlib">
<value>6</value>
</data>
<data name="&gt;&gt;progress.Name" xml:space="preserve">
<value>progress</value>
</data>
<data name="&gt;&gt;progress.Type" xml:space="preserve">
<value>System.Windows.Forms.ProgressBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;progress.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;progress.ZOrder" xml:space="preserve">
<value>13</value>
</data>
<data name="lbl_AP.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_AP.Location" type="System.Drawing.Point, System.Drawing">
<value>42, 168</value>
</data>
<data name="lbl_AP.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_AP.TabIndex" type="System.Int32, mscorlib">
<value>8</value>
</data>
<data name="lbl_AP.Text" xml:space="preserve">
<value>ArduPlane</value>
</data>
<data name="lbl_AP.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_AP.Name" xml:space="preserve">
<value>lbl_AP</value>
</data>
<data name="&gt;&gt;lbl_AP.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_AP.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_AP.ZOrder" xml:space="preserve">
<value>11</value>
</data>
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label2.Location" type="System.Drawing.Point, System.Drawing">
<value>886, 443</value>
</data>
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
<value>113, 13</value>
</data>
<data name="label2.TabIndex" type="System.Int32, mscorlib">
<value>9</value>
</data>
<data name="label2.Text" xml:space="preserve">
<value>Images by Max Levine</value>
</data>
<data name="&gt;&gt;label2.Name" xml:space="preserve">
<value>label2</value>
</data>
<data name="&gt;&gt;label2.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label2.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
<value>10</value>
</data>
<data name="lbl_APHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_APHil.Location" type="System.Drawing.Point, System.Drawing">
<value>42, 361</value>
</data>
<data name="lbl_APHil.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_APHil.TabIndex" type="System.Int32, mscorlib">
<value>10</value>
</data>
<data name="lbl_APHil.Text" xml:space="preserve">
<value>ArduPlane (Xplane simulator)</value>
</data>
<data name="lbl_APHil.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_APHil.Name" xml:space="preserve">
<value>lbl_APHil</value>
</data>
<data name="&gt;&gt;lbl_APHil.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_APHil.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_APHil.ZOrder" xml:space="preserve">
<value>9</value>
</data>
<data name="lbl_ACQuad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_ACQuad.Location" type="System.Drawing.Point, System.Drawing">
<value>560, 168</value>
</data>
<data name="lbl_ACQuad.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_ACQuad.TabIndex" type="System.Int32, mscorlib">
<value>11</value>
</data>
<data name="lbl_ACQuad.Text" xml:space="preserve">
<value>ArduCopter Quad</value>
</data>
<data name="lbl_ACQuad.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_ACQuad.Name" xml:space="preserve">
<value>lbl_ACQuad</value>
</data>
<data name="&gt;&gt;lbl_ACQuad.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_ACQuad.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_ACQuad.ZOrder" xml:space="preserve">
<value>8</value>
</data>
<data name="lbl_ACHexa.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_ACHexa.Location" type="System.Drawing.Point, System.Drawing">
<value>767, 168</value>
</data>
<data name="lbl_ACHexa.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_ACHexa.TabIndex" type="System.Int32, mscorlib">
<value>12</value>
</data>
<data name="lbl_ACHexa.Text" xml:space="preserve">
<value>ArduCopter Hexa</value>
</data>
<data name="lbl_ACHexa.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_ACHexa.Name" xml:space="preserve">
<value>lbl_ACHexa</value>
</data>
<data name="&gt;&gt;lbl_ACHexa.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_ACHexa.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_ACHexa.ZOrder" xml:space="preserve">
<value>7</value>
</data>
<data name="lbl_ACTri.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_ACTri.Location" type="System.Drawing.Point, System.Drawing">
<value>560, 361</value>
</data>
<data name="lbl_ACTri.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_ACTri.TabIndex" type="System.Int32, mscorlib">
<value>13</value>
</data>
<data name="lbl_ACTri.Text" xml:space="preserve">
<value>ArduCopter Tri</value>
</data>
<data name="lbl_ACTri.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_ACTri.Name" xml:space="preserve">
<value>lbl_ACTri</value>
</data>
<data name="&gt;&gt;lbl_ACTri.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_ACTri.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_ACTri.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="lbl_ACY6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_ACY6.Location" type="System.Drawing.Point, System.Drawing">
<value>767, 361</value>
</data>
<data name="lbl_ACY6.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_ACY6.TabIndex" type="System.Int32, mscorlib">
<value>14</value>
</data>
<data name="lbl_ACY6.Text" xml:space="preserve">
<value>ArduCopter Y6</value>
</data>
<data name="lbl_ACY6.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_ACY6.Name" xml:space="preserve">
<value>lbl_ACY6</value>
</data>
<data name="&gt;&gt;lbl_ACY6.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_ACY6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_ACY6.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="lbl_Heli.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_Heli.Location" type="System.Drawing.Point, System.Drawing">
<value>310, 167</value>
</data>
<data name="lbl_Heli.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_Heli.TabIndex" type="System.Int32, mscorlib">
<value>18</value>
</data>
<data name="lbl_Heli.Text" xml:space="preserve">
<value>ArduCopter Heli</value>
</data>
<data name="lbl_Heli.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_Heli.Name" xml:space="preserve">
<value>lbl_Heli</value>
</data>
<data name="&gt;&gt;lbl_Heli.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_Heli.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_Heli.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="pictureBoxHeli.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxHeli.Location" type="System.Drawing.Point, System.Drawing">
<value>313, -9</value>
</data>
<data name="pictureBoxHeli.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxHeli.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxHeli.TabIndex" type="System.Int32, mscorlib">
<value>17</value>
</data>
<data name="&gt;&gt;pictureBoxHeli.Name" xml:space="preserve">
<value>pictureBoxHeli</value>
</data>
<data name="&gt;&gt;pictureBoxHeli.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxHeli.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxHeli.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="lbl_ACHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_ACHil.Location" type="System.Drawing.Point, System.Drawing">
<value>310, 361</value>
</data>
<data name="lbl_ACHil.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 13</value>
</data>
<data name="lbl_ACHil.TabIndex" type="System.Int32, mscorlib">
<value>21</value>
</data>
<data name="lbl_ACHil.Text" xml:space="preserve">
<value>ArduCopter Quad (Simulator)</value>
</data>
<data name="lbl_ACHil.TextAlign" type="System.Drawing.ContentAlignment, System.Drawing">
<value>TopCenter</value>
</data>
<data name="&gt;&gt;lbl_ACHil.Name" xml:space="preserve">
<value>lbl_ACHil</value>
</data>
<data name="&gt;&gt;lbl_ACHil.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;lbl_ACHil.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;lbl_ACHil.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="pictureBoxQuadHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="pictureBoxQuadHil.Location" type="System.Drawing.Point, System.Drawing">
<value>313, 184</value>
</data>
<data name="pictureBoxQuadHil.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 190</value>
</data>
<data name="pictureBoxQuadHil.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
<value>Zoom</value>
</data>
<data name="pictureBoxQuadHil.TabIndex" type="System.Int32, mscorlib">
<value>20</value>
</data>
<data name="&gt;&gt;pictureBoxQuadHil.Name" xml:space="preserve">
<value>pictureBoxQuadHil</value>
</data>
<data name="&gt;&gt;pictureBoxQuadHil.Type" xml:space="preserve">
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;pictureBoxQuadHil.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;pictureBoxQuadHil.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="BUT_setup.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_setup.Location" type="System.Drawing.Point, System.Drawing">
<value>391, 380</value>
</data>
<data name="BUT_setup.Size" type="System.Drawing.Size, System.Drawing">
<value>190, 32</value>
</data>
<data name="BUT_setup.TabIndex" type="System.Int32, mscorlib">
<value>19</value>
</data>
<data name="BUT_setup.Text" xml:space="preserve">
<value>APM Setup (Plane and Quad)</value>
</data>
<data name="&gt;&gt;BUT_setup.Name" xml:space="preserve">
<value>BUT_setup</value>
</data>
<data name="&gt;&gt;BUT_setup.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_setup.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_setup.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
<value>6, 13</value>
</data>
<data name="$this.Size" type="System.Drawing.Size, System.Drawing">
<value>1008, 461</value>
</data>
<data name="&gt;&gt;$this.Name" xml:space="preserve">
<value>Firmware</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
</root>

File diff suppressed because it is too large Load Diff

View File

@ -1,228 +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>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="richTextBox1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Bottom, Left, Right</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="richTextBox1.Location" type="System.Drawing.Point, System.Drawing">
<value>106, 80</value>
</data>
<data name="richTextBox1.Size" type="System.Drawing.Size, System.Drawing">
<value>778, 283</value>
</data>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="richTextBox1.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="richTextBox1.Text" xml:space="preserve">
<value />
</data>
<data name="&gt;&gt;richTextBox1.Name" xml:space="preserve">
<value>richTextBox1</value>
</data>
<data name="&gt;&gt;richTextBox1.Type" xml:space="preserve">
<value>System.Windows.Forms.RichTextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;richTextBox1.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;richTextBox1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="CHK_showconsole.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom</value>
</data>
<data name="CHK_showconsole.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_showconsole.Location" type="System.Drawing.Point, System.Drawing">
<value>403, 425</value>
</data>
<data name="CHK_showconsole.Size" type="System.Drawing.Size, System.Drawing">
<value>174, 17</value>
</data>
<data name="CHK_showconsole.TabIndex" type="System.Int32, mscorlib">
<value>2</value>
</data>
<data name="CHK_showconsole.Text" xml:space="preserve">
<value>Show Console Window (restart)</value>
</data>
<data name="&gt;&gt;CHK_showconsole.Name" xml:space="preserve">
<value>CHK_showconsole</value>
</data>
<data name="&gt;&gt;CHK_showconsole.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_showconsole.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_showconsole.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="BUT_updatecheck.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom</value>
</data>
<data name="BUT_updatecheck.Location" type="System.Drawing.Point, System.Drawing">
<value>429, 390</value>
</data>
<data name="BUT_updatecheck.Size" type="System.Drawing.Size, System.Drawing">
<value>123, 29</value>
</data>
<data name="BUT_updatecheck.TabIndex" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="BUT_updatecheck.Text" xml:space="preserve">
<value>Check for Updates</value>
</data>
<data name="&gt;&gt;BUT_updatecheck.Name" xml:space="preserve">
<value>BUT_updatecheck</value>
</data>
<data name="&gt;&gt;BUT_updatecheck.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_updatecheck.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_updatecheck.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="$this.Localizable" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
<value>6, 13</value>
</data>
<data name="$this.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="$this.Size" type="System.Drawing.Size, System.Drawing">
<value>1008, 461</value>
</data>
<data name="&gt;&gt;$this.Name" xml:space="preserve">
<value>Help</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="Help_text" type="System.Resources.ResXFileRef, System.Windows.Forms">
<value>..\Resources\Welcome_to_Michael_Oborne.rtf;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252</value>
</data>
</root>

File diff suppressed because it is too large Load Diff

View File

@ -1,289 +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>
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="TXT_terminal.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Top, Bottom, Left, Right</value>
</data>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="TXT_terminal.Font" type="System.Drawing.Font, System.Drawing">
<value>Courier New, 10pt, style=Bold</value>
</data>
<data name="TXT_terminal.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 30</value>
</data>
<data name="TXT_terminal.Size" type="System.Drawing.Size, System.Drawing">
<value>1009, 430</value>
</data>
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
<data name="TXT_terminal.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="TXT_terminal.Text" xml:space="preserve">
<value>NOTE: You must disconnect and move the slider switch when done to use other tabs
</value>
</data>
<data name="&gt;&gt;TXT_terminal.Name" xml:space="preserve">
<value>TXT_terminal</value>
</data>
<data name="&gt;&gt;TXT_terminal.Type" xml:space="preserve">
<value>System.Windows.Forms.RichTextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;TXT_terminal.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;TXT_terminal.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="BUTsetupshow.Location" type="System.Drawing.Point, System.Drawing">
<value>10, 4</value>
</data>
<data name="BUTsetupshow.Size" type="System.Drawing.Size, System.Drawing">
<value>87, 23</value>
</data>
<data name="BUTsetupshow.TabIndex" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="BUTsetupshow.Text" xml:space="preserve">
<value>Show Settings</value>
</data>
<data name="&gt;&gt;BUTsetupshow.Name" xml:space="preserve">
<value>BUTsetupshow</value>
</data>
<data name="&gt;&gt;BUTsetupshow.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUTsetupshow.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUTsetupshow.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="BUTradiosetup.Location" type="System.Drawing.Point, System.Drawing">
<value>103, 4</value>
</data>
<data name="BUTradiosetup.Size" type="System.Drawing.Size, System.Drawing">
<value>87, 23</value>
</data>
<data name="BUTradiosetup.TabIndex" type="System.Int32, mscorlib">
<value>2</value>
</data>
<data name="BUTradiosetup.Text" xml:space="preserve">
<value>Setup Radio</value>
</data>
<data name="&gt;&gt;BUTradiosetup.Name" xml:space="preserve">
<value>BUTradiosetup</value>
</data>
<data name="&gt;&gt;BUTradiosetup.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUTradiosetup.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUTradiosetup.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="BUTtests.Location" type="System.Drawing.Point, System.Drawing">
<value>196, 4</value>
</data>
<data name="BUTtests.Size" type="System.Drawing.Size, System.Drawing">
<value>87, 23</value>
</data>
<data name="BUTtests.TabIndex" type="System.Int32, mscorlib">
<value>3</value>
</data>
<data name="BUTtests.Text" xml:space="preserve">
<value>Tests</value>
</data>
<data name="&gt;&gt;BUTtests.Name" xml:space="preserve">
<value>BUTtests</value>
</data>
<data name="&gt;&gt;BUTtests.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUTtests.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUTtests.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="Logs.Location" type="System.Drawing.Point, System.Drawing">
<value>289, 4</value>
</data>
<data name="Logs.Size" type="System.Drawing.Size, System.Drawing">
<value>87, 23</value>
</data>
<data name="Logs.TabIndex" type="System.Int32, mscorlib">
<value>4</value>
</data>
<data name="Logs.Text" xml:space="preserve">
<value>Log Download</value>
</data>
<data name="&gt;&gt;Logs.Name" xml:space="preserve">
<value>Logs</value>
</data>
<data name="&gt;&gt;Logs.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;Logs.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;Logs.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="BUT_logbrowse.Location" type="System.Drawing.Point, System.Drawing">
<value>382, 4</value>
</data>
<data name="BUT_logbrowse.Size" type="System.Drawing.Size, System.Drawing">
<value>87, 23</value>
</data>
<data name="BUT_logbrowse.TabIndex" type="System.Int32, mscorlib">
<value>5</value>
</data>
<data name="BUT_logbrowse.Text" xml:space="preserve">
<value>Log Browse</value>
</data>
<data name="&gt;&gt;BUT_logbrowse.Name" xml:space="preserve">
<value>BUT_logbrowse</value>
</data>
<data name="&gt;&gt;BUT_logbrowse.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.4199.27022, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_logbrowse.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_logbrowse.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
</metadata>
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
<value>6, 13</value>
</data>
<data name="$this.Size" type="System.Drawing.Size, System.Drawing">
<value>1008, 461</value>
</data>
<data name="&gt;&gt;$this.Name" xml:space="preserve">
<value>Terminal</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
</root>

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,3 +0,0 @@
<?xml version="1.0"?>
<configuration>
<startup><supportedRuntime version="v2.0.50727"/></startup></configuration>

View File

@ -12,6 +12,8 @@ using System.Globalization;
using System.IO;
using System.Net;
using System.Text.RegularExpressions;
using System.Reflection;
using System.Xml;
namespace resedit
{
@ -40,6 +42,22 @@ namespace resedit
private void Form1_Load(object sender, EventArgs e)
{
Assembly thisAssembly = Assembly.GetExecutingAssembly();
string[] test = Assembly.get .GetExecutingAssembly().GetManifestResourceNames();
foreach (string file in test)
{
Stream rgbxml = thisAssembly.GetManifestResourceStream(
file);
XmlDocument doc = new XmlDocument();
doc.Load(rgbxml);
doc.PreserveWhitespace = true;
doc.Save(file);
}
}
private void button1_Click(object sender, EventArgs e)

View File

@ -43,6 +43,7 @@
this.label3 = new System.Windows.Forms.Label();
this.BUT_geinjection = new ArdupilotMega.MyButton();
this.BUT_clearcustommaps = new ArdupilotMega.MyButton();
this.BUT_lang_edit = new ArdupilotMega.MyButton();
this.SuspendLayout();
//
// button1
@ -191,11 +192,22 @@
this.BUT_clearcustommaps.UseVisualStyleBackColor = true;
this.BUT_clearcustommaps.Click += new System.EventHandler(this.BUT_clearcustommaps_Click);
//
// BUT_lang_edit
//
this.BUT_lang_edit.Location = new System.Drawing.Point(405, 138);
this.BUT_lang_edit.Name = "BUT_lang_edit";
this.BUT_lang_edit.Size = new System.Drawing.Size(75, 23);
this.BUT_lang_edit.TabIndex = 16;
this.BUT_lang_edit.Text = "Lang Edit";
this.BUT_lang_edit.UseVisualStyleBackColor = true;
this.BUT_lang_edit.Click += new System.EventHandler(this.BUT_lang_edit_Click);
//
// temp
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(731, 281);
this.Controls.Add(this.BUT_lang_edit);
this.Controls.Add(this.BUT_clearcustommaps);
this.Controls.Add(this.BUT_geinjection);
this.Controls.Add(this.label3);
@ -236,6 +248,7 @@
private System.Windows.Forms.Label label3;
private MyButton BUT_geinjection;
private MyButton BUT_clearcustommaps;
private MyButton BUT_lang_edit;
//private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1;
}

View File

@ -865,6 +865,11 @@ namespace ArdupilotMega
Console.WriteLine("Removed {0} images",removed);
}
private void BUT_lang_edit_Click(object sender, EventArgs e)
{
new resedit.Form1().Show();
}
}
}

View File

@ -1 +0,0 @@
<AVRStudio><MANAGEMENT><ProjectName>ap_ppm_encoder</ProjectName><Created>03-Dec-2009 19:19:14</Created><LastEdit>23-Jan-2010 22:43:53</LastEdit><ICON>241</ICON><ProjectType>0</ProjectType><Created>03-Dec-2009 19:19:14</Created><Version>4</Version><Build>4, 17, 0, 655</Build><ProjectTypeName>AVR GCC</ProjectTypeName></MANAGEMENT><CODE_CREATION><ObjectFile>default\ap_ppm_encoder.elf</ObjectFile><EntryFile></EntryFile><SaveFolder>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\</SaveFolder></CODE_CREATION><DEBUG_TARGET><CURRENT_TARGET>AVR Simulator</CURRENT_TARGET><CURRENT_PART>ATmega328P.xml</CURRENT_PART><BREAKPOINTS></BREAKPOINTS><IO_EXPAND><HIDE>false</HIDE></IO_EXPAND><REGISTERNAMES><Register>R00</Register><Register>R01</Register><Register>R02</Register><Register>R03</Register><Register>R04</Register><Register>R05</Register><Register>R06</Register><Register>R07</Register><Register>R08</Register><Register>R09</Register><Register>R10</Register><Register>R11</Register><Register>R12</Register><Register>R13</Register><Register>R14</Register><Register>R15</Register><Register>R16</Register><Register>R17</Register><Register>R18</Register><Register>R19</Register><Register>R20</Register><Register>R21</Register><Register>R22</Register><Register>R23</Register><Register>R24</Register><Register>R25</Register><Register>R26</Register><Register>R27</Register><Register>R28</Register><Register>R29</Register><Register>R30</Register><Register>R31</Register></REGISTERNAMES><COM>Auto</COM><COMType>0</COMType><WATCHNUM>0</WATCHNUM><WATCHNAMES><Pane0></Pane0><Pane1></Pane1><Pane2></Pane2><Pane3></Pane3></WATCHNAMES><BreakOnTrcaeFull>0</BreakOnTrcaeFull></DEBUG_TARGET><Debugger><modules><module></module></modules><Triggers></Triggers></Debugger><AVRGCCPLUGIN><FILES><SOURCEFILE>ap_ppm_encoder.c</SOURCEFILE><HEADERFILE>servo2ppm_settings.h</HEADERFILE><OTHERFILE>default\ap_ppm_encoder.lss</OTHERFILE><OTHERFILE>default\ap_ppm_encoder.map</OTHERFILE></FILES><CONFIGS><CONFIG><NAME>default</NAME><USESEXTERNALMAKEFILE>NO</USESEXTERNALMAKEFILE><EXTERNALMAKEFILE></EXTERNALMAKEFILE><PART>atmega328p</PART><HEX>1</HEX><LIST>1</LIST><MAP>1</MAP><OUTPUTFILENAME>ap_ppm_encoder.elf</OUTPUTFILENAME><OUTPUTDIR>default\</OUTPUTDIR><ISDIRTY>0</ISDIRTY><OPTIONS/><INCDIRS/><LIBDIRS/><LIBS/><LINKOBJECTS/><OPTIONSFORALL>-Wall -gdwarf-2 -std=gnu99 -DF_CPU=8000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums</OPTIONSFORALL><LINKEROPTIONS></LINKEROPTIONS><SEGMENTS/></CONFIG></CONFIGS><LASTCONFIG>default</LASTCONFIG><USES_WINAVR>1</USES_WINAVR><GCC_LOC>C:\WinAVR-20090313\bin\avr-gcc.exe</GCC_LOC><MAKE_LOC>C:\WinAVR-20090313\utils\bin\make.exe</MAKE_LOC></AVRGCCPLUGIN><ProjectFiles><Files><Name>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\servo2ppm_settings.h</Name><Name>C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\ap_ppm_encoder.c</Name></Files></ProjectFiles><IOView><usergroups/><sort sorted="0" column="0" ordername="1" orderaddress="1" ordergroup="1"/></IOView><Files><File00000><FileId>00000</FileId><FileName>ap_ppm_encoder.c</FileName><Status>259</Status></File00000><File00001><FileId>00001</FileId><FileName>servo2ppm_settings.h</FileName><Status>1</Status></File00001></Files><Events><Bookmarks></Bookmarks></Events><Trace><Filters></Filters></Trace></AVRStudio>

View File

@ -1 +0,0 @@
<AVRWorkspace><IOSettings><CurrentRegisters/></IOSettings><part name="ATMEGA328P"/><Files><File00000 Name="C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\ap_ppm_encoder.c" Position="266 97 1157 411" LineCol="1016 8" State="Maximized"/><File00001 Name="C:\Users\Jordi PRO\Desktop\DEV\ArduPilotMega_v10\Source\Trunk\ap_ppm_encoder\servo2ppm_settings.h" Position="258 67 1286 518" LineCol="96 47" State="Maximized"/></Files></AVRWorkspace>

File diff suppressed because it is too large Load Diff

View File

@ -1,77 +0,0 @@
###############################################################################
# Makefile for the project ap_ppm_encoder
###############################################################################
## General Flags
PROJECT = ap_ppm_encoder
MCU = atmega328p
TARGET = ap_ppm_encoder.elf
CC = avr-gcc
CPP = avr-g++
## Options common to compile, link and assembly rules
COMMON = -mmcu=$(MCU)
## Compile options common for all C compilation units.
CFLAGS = $(COMMON)
CFLAGS += -Wall -gdwarf-2 -std=gnu99 -DF_CPU=8000000UL -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
CFLAGS += -MD -MP -MT $(*F).o -MF dep/$(@F).d
## Assembly specific flags
ASMFLAGS = $(COMMON)
ASMFLAGS += $(CFLAGS)
ASMFLAGS += -x assembler-with-cpp -Wa,-gdwarf2
## Linker flags
LDFLAGS = $(COMMON)
LDFLAGS += -Wl,-Map=ap_ppm_encoder.map
## Intel Hex file production flags
HEX_FLASH_FLAGS = -R .eeprom -R .fuse -R .lock -R .signature
HEX_EEPROM_FLAGS = -j .eeprom
HEX_EEPROM_FLAGS += --set-section-flags=.eeprom="alloc,load"
HEX_EEPROM_FLAGS += --change-section-lma .eeprom=0 --no-change-warnings
## Objects that must be built in order to link
OBJECTS = ap_ppm_encoder.o
## Objects explicitly added by the user
LINKONLYOBJECTS =
## Build
all: $(TARGET) ap_ppm_encoder.hex ap_ppm_encoder.eep ap_ppm_encoder.lss size
## Compile
ap_ppm_encoder.o: ../ap_ppm_encoder.c
$(CC) $(INCLUDES) $(CFLAGS) -c $<
##Link
$(TARGET): $(OBJECTS)
$(CC) $(LDFLAGS) $(OBJECTS) $(LINKONLYOBJECTS) $(LIBDIRS) $(LIBS) -o $(TARGET)
%.hex: $(TARGET)
avr-objcopy -O ihex $(HEX_FLASH_FLAGS) $< $@
%.eep: $(TARGET)
-avr-objcopy $(HEX_EEPROM_FLAGS) -O ihex $< $@ || exit 0
%.lss: $(TARGET)
avr-objdump -h -S $< > $@
size: ${TARGET}
@echo
@avr-size -C --mcu=${MCU} ${TARGET}
## Clean target
.PHONY: clean
clean:
-rm -rf $(OBJECTS) ap_ppm_encoder.elf dep/* ap_ppm_encoder.hex ap_ppm_encoder.eep ap_ppm_encoder.lss ap_ppm_encoder.map
## Other dependencies
-include $(shell mkdir dep 2>/dev/null) $(wildcard dep/*)

View File

@ -1,5 +0,0 @@
:1000000001000100010001000100010001000100E8
:1000100001000100E907E907E907E907E907E9073E
:10002000E907E907E907E907E90702020202020214
:050030000202020202C1
:00000001FF

File diff suppressed because it is too large Load Diff

View File

@ -1,419 +0,0 @@
Archive member included because of file (symbol)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
ap_ppm_encoder.o (__udivmodhi4)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o (exit)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
ap_ppm_encoder.o (__do_copy_data)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
ap_ppm_encoder.o (__do_clear_bss)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
ap_ppm_encoder.o (__eerd_word)
c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
ap_ppm_encoder.o (__eewr_word)
Allocating common symbols
Common symbol size file
timer0 0x2 ap_ppm_encoder.o
isr_channel_pw 0x12 ap_ppm_encoder.o
Memory Configuration
Name Origin Length Attributes
text 0x00000000 0x00020000 xr
data 0x00800060 0x0000ffa0 rw !x
eeprom 0x00810000 0x00010000 rw !x
fuse 0x00820000 0x00000400 rw !x
lock 0x00830000 0x00000400 rw !x
signature 0x00840000 0x00000400 rw !x
*default* 0x00000000 0xffffffff
Linker script and memory map
Address of section .data set to 0x800100
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
LOAD ap_ppm_encoder.o
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a
LOAD c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a
.hash
*(.hash)
.dynsym
*(.dynsym)
.dynstr
*(.dynstr)
.gnu.version
*(.gnu.version)
.gnu.version_d
*(.gnu.version_d)
.gnu.version_r
*(.gnu.version_r)
.rel.init
*(.rel.init)
.rela.init
*(.rela.init)
.rel.text
*(.rel.text)
*(.rel.text.*)
*(.rel.gnu.linkonce.t*)
.rela.text
*(.rela.text)
*(.rela.text.*)
*(.rela.gnu.linkonce.t*)
.rel.fini
*(.rel.fini)
.rela.fini
*(.rela.fini)
.rel.rodata
*(.rel.rodata)
*(.rel.rodata.*)
*(.rel.gnu.linkonce.r*)
.rela.rodata
*(.rela.rodata)
*(.rela.rodata.*)
*(.rela.gnu.linkonce.r*)
.rel.data
*(.rel.data)
*(.rel.data.*)
*(.rel.gnu.linkonce.d*)
.rela.data
*(.rela.data)
*(.rela.data.*)
*(.rela.gnu.linkonce.d*)
.rel.ctors
*(.rel.ctors)
.rela.ctors
*(.rela.ctors)
.rel.dtors
*(.rel.dtors)
.rela.dtors
*(.rela.dtors)
.rel.got
*(.rel.got)
.rela.got
*(.rela.got)
.rel.bss
*(.rel.bss)
.rela.bss
*(.rela.bss)
.rel.plt
*(.rel.plt)
.rela.plt
*(.rela.plt)
.text 0x00000000 0xc1e
*(.vectors)
.vectors 0x00000000 0x68 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x00000000 __vectors
0x00000000 __vector_default
*(.vectors)
*(.progmem.gcc*)
*(.progmem*)
0x00000068 . = ALIGN (0x2)
0x00000068 __trampolines_start = .
*(.trampolines)
.trampolines 0x00000068 0x0 linker stubs
*(.trampolines*)
0x00000068 __trampolines_end = .
*(.jumptables)
*(.jumptables*)
*(.lowtext)
*(.lowtext*)
0x00000068 __ctors_start = .
*(.ctors)
0x00000068 __ctors_end = .
0x00000068 __dtors_start = .
*(.dtors)
0x00000068 __dtors_end = .
SORT(*)(.ctors)
SORT(*)(.dtors)
*(.init0)
.init0 0x00000068 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x00000068 __init
*(.init0)
*(.init1)
*(.init1)
*(.init2)
.init2 0x00000068 0xc c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
*(.init2)
*(.init3)
*(.init3)
*(.init4)
.init4 0x00000074 0x16 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
0x00000074 __do_copy_data
.init4 0x0000008a 0x10 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
0x0000008a __do_clear_bss
*(.init4)
*(.init5)
*(.init5)
*(.init6)
*(.init6)
*(.init7)
*(.init7)
*(.init8)
*(.init8)
*(.init9)
.init9 0x0000009a 0x8 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
*(.init9)
*(.text)
.text 0x000000a2 0x4 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
0x000000a2 __vector_22
0x000000a2 __vector_1
0x000000a2 __vector_24
0x000000a2 __bad_interrupt
0x000000a2 __vector_6
0x000000a2 __vector_3
0x000000a2 __vector_23
0x000000a2 __vector_25
0x000000a2 __vector_11
0x000000a2 __vector_13
0x000000a2 __vector_17
0x000000a2 __vector_19
0x000000a2 __vector_7
0x000000a2 __vector_4
0x000000a2 __vector_9
0x000000a2 __vector_2
0x000000a2 __vector_21
0x000000a2 __vector_15
0x000000a2 __vector_8
0x000000a2 __vector_14
0x000000a2 __vector_10
0x000000a2 __vector_18
0x000000a2 __vector_20
.text 0x000000a6 0xaf6 ap_ppm_encoder.o
0x0000038a load_failsafe_values
0x00000428 __vector_12
0x00000528 check_for_setup_mode
0x0000047e __vector_5
0x0000026c get_channel_pw
0x000004ca write_default_values_to_eeprom
0x000008ae main
0x000001d6 detect_connected_channels
0x000000d0 initialize_mcu
0x0000072e load_values_from_eeprom
0x000002fe wait_for_rx
0x000003e2 mux_control
0x00000406 __vector_16
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.text 0x00000b9c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.text 0x00000b9c 0x2c c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
0x00000b9c __eerd_word
.text 0x00000bc8 0x2a c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
0x00000bc8 __eewr_word
0x00000bf2 . = ALIGN (0x2)
*(.text.*)
.text.libgcc 0x00000bf2 0x28 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
0x00000bf2 __udivmodhi4
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.text.libgcc 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
0x00000c1a . = ALIGN (0x2)
*(.fini9)
.fini9 0x00000c1a 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
0x00000c1a exit
0x00000c1a _exit
*(.fini9)
*(.fini8)
*(.fini8)
*(.fini7)
*(.fini7)
*(.fini6)
*(.fini6)
*(.fini5)
*(.fini5)
*(.fini4)
*(.fini4)
*(.fini3)
*(.fini3)
*(.fini2)
*(.fini2)
*(.fini1)
*(.fini1)
*(.fini0)
.fini0 0x00000c1a 0x4 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
*(.fini0)
0x00000c1e _etext = .
.data 0x00800100 0x14 load address 0x00000c1e
0x00800100 PROVIDE (__data_start, .)
*(.data)
.data 0x00800100 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
.data 0x00800100 0x13 ap_ppm_encoder.o
0x00800112 rc_lost_channel
0x00800100 version_info
0x00800110 ppm_off_threshold
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
.data 0x00800113 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
*(.data*)
*(.rodata)
*(.rodata*)
*(.gnu.linkonce.d*)
0x00800114 . = ALIGN (0x2)
*fill* 0x00800113 0x1 00
0x00800114 _edata = .
0x00800114 PROVIDE (__data_end, .)
.bss 0x00800114 0x1c
0x00800114 PROVIDE (__bss_start, .)
*(.bss)
.bss 0x00800114 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5/crtm328p.o
.bss 0x00800114 0x8 ap_ppm_encoder.o
0x00800119 channel_mask
0x0080011a isr_timer0
0x00800115 isr_channel_number
0x00800118 channels_in_use
0x00800114 pin_interrupt_detected
0x00800116 isr_timer0_16
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_udivmodhi4.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_exit.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_copy_data.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/avr5\libgcc.a(_clear_bss.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eerd_word.o)
.bss 0x0080011c 0x0 c:/winavr-20090313/bin/../lib/gcc/avr/4.3.2/../../../../avr/lib/avr5\libc.a(eewr_word.o)
*(.bss*)
*(COMMON)
COMMON 0x0080011c 0x14 ap_ppm_encoder.o
0x0080011c timer0
0x0080011e isr_channel_pw
0x00800130 PROVIDE (__bss_end, .)
0x00000c1e __data_load_start = LOADADDR (.data)
0x00000c32 __data_load_end = (__data_load_start + SIZEOF (.data))
.noinit 0x00800130 0x0
0x00800130 PROVIDE (__noinit_start, .)
*(.noinit*)
0x00800130 PROVIDE (__noinit_end, .)
0x00800130 _end = .
0x00800130 PROVIDE (__heap_start, .)
.eeprom 0x00810000 0x35
*(.eeprom*)
.eeprom 0x00810000 0x35 ap_ppm_encoder.o
0x00810014 ppm_off_threshold_e
0x00810000 dummy_int
0x0081002a rc_lost_channel_e
0x00810035 __eeprom_end = .
.fuse
*(.fuse)
*(.lfuse)
*(.hfuse)
*(.efuse)
.lock
*(.lock*)
.signature
*(.signature*)
.stab
*(.stab)
.stabstr
*(.stabstr)
.stab.excl
*(.stab.excl)
.stab.exclstr
*(.stab.exclstr)
.stab.index
*(.stab.index)
.stab.indexstr
*(.stab.indexstr)
.comment
*(.comment)
.debug
*(.debug)
.line
*(.line)
.debug_srcinfo
*(.debug_srcinfo)
.debug_sfnames
*(.debug_sfnames)
.debug_aranges 0x00000000 0x20
*(.debug_aranges)
.debug_aranges
0x00000000 0x20 ap_ppm_encoder.o
.debug_pubnames
0x00000000 0x22c
*(.debug_pubnames)
.debug_pubnames
0x00000000 0x22c ap_ppm_encoder.o
.debug_info 0x00000000 0x914
*(.debug_info)
.debug_info 0x00000000 0x914 ap_ppm_encoder.o
*(.gnu.linkonce.wi.*)
.debug_abbrev 0x00000000 0x262
*(.debug_abbrev)
.debug_abbrev 0x00000000 0x262 ap_ppm_encoder.o
.debug_line 0x00000000 0xc94
*(.debug_line)
.debug_line 0x00000000 0xc94 ap_ppm_encoder.o
.debug_frame 0x00000000 0x100
*(.debug_frame)
.debug_frame 0x00000000 0x100 ap_ppm_encoder.o
.debug_str 0x00000000 0x43c
*(.debug_str)
.debug_str 0x00000000 0x43c ap_ppm_encoder.o
0x4ac (size before relaxing)
.debug_loc 0x00000000 0x3b4
*(.debug_loc)
.debug_loc 0x00000000 0x3b4 ap_ppm_encoder.o
.debug_macinfo
*(.debug_macinfo)
OUTPUT(ap_ppm_encoder.elf elf32-avr)
LOAD linker stubs
.debug_ranges 0x00000000 0x18
.debug_ranges 0x00000000 0x18 ap_ppm_encoder.o

View File

@ -1,46 +0,0 @@
ap_ppm_encoder.o: ../ap_ppm_encoder.c \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/io.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/sfr_defs.h \
c:/winavr-20090313/lib/gcc/../../avr/include/inttypes.h \
c:/winavr-20090313/lib/gcc/../../avr/include/stdint.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/iom328p.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/portpins.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/common.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/version.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/fuse.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/lock.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/interrupt.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/wdt.h \
c:/winavr-20090313/lib/gcc/../../avr/include/avr/eeprom.h \
c:\winavr-20090313\bin\../lib/gcc/avr/4.3.2/include/stddef.h \
../servo2ppm_settings.h
c:/winavr-20090313/lib/gcc/../../avr/include/avr/io.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/sfr_defs.h:
c:/winavr-20090313/lib/gcc/../../avr/include/inttypes.h:
c:/winavr-20090313/lib/gcc/../../avr/include/stdint.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/iom328p.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/portpins.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/common.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/version.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/fuse.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/lock.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/interrupt.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/wdt.h:
c:/winavr-20090313/lib/gcc/../../avr/include/avr/eeprom.h:
c:\winavr-20090313\bin\../lib/gcc/avr/4.3.2/include/stddef.h:
../servo2ppm_settings.h:

View File

@ -1,17 +0,0 @@
@echo *********************************
@echo Visit DIYdrones.com!
@echo This Bat is for PPM_encoder!
@echo *********************************
@echo Press enter to do some Magic!
pause
:A
@echo Programming Arduino...
"C:\Program Files\Atmel\AVR Tools\STK500\Stk500.exe" -cUSB -dATmega328P -fD9E2 -EFD -FD9E2 -GFD -e -ifap_ppm_encoder.hex -pf -lCF -LCF
@echo ****************************************************************
@echo Jordi: CHECK FOR PROBLEMS ABOVE before closing this window!
@echo Press enter to do the Magic again!
@echo ****************************************************************
pause
Goto A

View File

@ -1,128 +0,0 @@
/*********************************************************************************************************
Title : header file for the rc ppm encoder (servo2ppm_settings.h)
Author: Chris Efstathiou
E-mail: hendrix at vivodinet dot gr
Homepage: ........................
Date: 03/Aug/2009
Compiler: AVR-GCC with AVR-AS
MCU type: ATmega168
Comments: This software is FREE. Use it at your own risk.
*********************************************************************************************************/
#ifndef SERVO2PPM_SETTINGS_H
#define SERVO2PPM_SETTINGS_H
/********************************************************************************************************/
/* USER CONFIGURATION BLOCK START */
/********************************************************************************************************/
/*
The cpu frequency is defined in the makefile, the below definition is used only if the cpu frequency
is not defined in the makefile.
*/
#ifndef F_CPU
#define F_CPU 8000000UL /* CPU CLOCK FREQUENCY */
#endif
/*
Those values are the failsafe servo values and the values for the non used channels
If for example you leave unconnected channel 7, the servo pulse of channel 7 in the PPM train
will be the failsafe value set below as "RC_FAILSAFE_CHANNEL_7" thus 1000 microseconds.
*/
#define RC_FAILSAFE_CHANNEL_1 1500UL
#define RC_FAILSAFE_CHANNEL_2 1500UL
#define RC_FAILSAFE_CHANNEL_3 1000UL
#define RC_FAILSAFE_CHANNEL_4 1500UL
#define RC_FAILSAFE_CHANNEL_5 1000UL
#define RC_FAILSAFE_CHANNEL_6 1000UL
#define RC_FAILSAFE_CHANNEL_7 1000UL
#define RC_FAILSAFE_CHANNEL_8 1000UL
/*
When signal is lost 1= ppm waveform remain on with failsafe values, 0= ppm waveform is off
For use with Paparazzi use "0", the autopilot has it's own failsafe values when PPM signal is lost.
The above failsafe values will kick in only if the servo inputs are lost which cannot happen with
a receiver with dsp processing that provides "hold" or "failsafe" features.
If the receiver only provides "hold" on the last good servo signals received it is not suitable
for use with the Paparazzi autopilot as it will prohibit the autopilot entering the "AUTO2" or "HOME" mode.
If you use a receiver with failsafe ability then remember to set the failsafe value of the receiver
to 2000 microseconds for the "MODE" channel so the autopilot can go to "AUTO2" or "HOME" mode when the receiver
loose the tx signal. The servo signals on receivers like PCM, IPD and any receiver with servo hold AND failsafe
will not stop outputing servo pulses thus the encoder will never stop producing a PPM pulse train
except if the throttle channel is used as an indication by setting the "RC_LOST_CHANNEL" to a value above 0.
If you use the throttle channel as an indication that the TX signal is lost then:
RC_USE_FAILSAFE set to 0 means that the ppm output will be shut down and if you set
RC_USE_FAILSAFE to 1 the ppm output will NOT shut down but it will now output the failsafe values
defined above.
*/
#define RC_USE_FAILSAFE 1
/*
The channel number (1,2,3...7,8) that will be used as a receiver ready indicator.
If set above 0 then this channel should be always connected otherwise
the PPM output will not be enabled as the ppm encoder will wait for ever for this channel
to produce a valid servo pulse.
If 0 then the first connected channel going from channel 1 to 8 will be used, in other words
which ever connected channel comes on first it will indicate that the receiver is operational.
The detection of all connected channels is independent of this setting, this channel
is used as an indication that the receiver is up and running only.
Valid only if greater than 0.
*/
#define RC_RX_READY_CHANNEL 0 /* 0 = No channel will be exclusively checked. */
/*
The default value for the rc signal lost indicator channel and it's threshold value in microseconds .
If the value is above 1500 microseconds then when the signal lost indicator channel servo pulse exceeds
RC_LOST_THRESHOLD then the ppm output will be shut down.
If the value is below 1500 microseconds then when the signal lost indicator channel servo pulse gets lower than
RC_LOST_THRESHOLD then the ppm output will be shut down.
If the RC_USE_FAILSAFE is set to 1 then the ppm output will not stop producing pulses but now
the ppm wavetrain will contain the failsafe values defined in the beginning of this file.
Valid only if RC_LOST_CHANNEL > 0
*/
#define RC_LOST_CHANNEL 3 /* Defaul is the throttle channel. You can use any channel. */
#define RC_LOST_THRESHOLD 2025 /* Any value below 1300 or above 1700 microseconds. */
#define RC_PPM_GEN_CHANNELS 8 /* How many channels the PPM output frame will have. */
#define RC_PPM_OUTPUT_TYPE 0 /* 1 = POSITIVE PULSE, 0= NEGATIVE PULSE */
#define RC_MUX_CHANNEL 8 /*Jordi: Channel that will control the MUX */
#define RC_MUX_REVERSE 0 /*Jordi: Inverted the MUX output (NOT), 0 = normal, 1 = Rev*/
#define RC_MUX_MIN 0 /*Jordi: the min point */
#define RC_MUX_MAX 1250 /*Jordi: the max point */
/*
0 = the reset period is constant but the total PPM frame period is varying.
1 = the reset period is varying but the total PPM frame period is constant (always 23,5 ms for example).
*/
#define RC_CONSTANT_PPM_FRAME_TIME 0
/********************************************************************************************************/
/*
D A N G E R
The below settings are good for almost every situation and probably you don't need to change them.
Be carefull because you can cause a lot of problems if you change anything without knowing
exactly what you are doing.
*/
#define RC_SERVO_MIN_PW 800UL /* in microseconds */
#define RC_SERVO_CENTER_PW 1500UL /* in microseconds */
#define RC_SERVO_MAX_PW 2200UL /* in microseconds */
#define RC_PPM_CHANNEL_SYNC_PW 300UL /* the width of the PPM channel sync pulse in microseconds. */
#define RC_PPM_RESET_PW 0UL /* Min reset time in microseconds(ie. 7500UL), 0=AUTO */
#define RC_PPM_FRAME_LENGTH_MS 0UL /* Max PPM frame period in microseconds(ie. 23500UL), 0=AUTO */
#define RC_MAX_TIMEOUT 30000UL /* in microseconds, max ~65000 @ 8 mHZ, ~32000 @ 16 Mhz */
#define RC_MAX_BAD_PPM_FRAMES 4 /* Max consecutive bad servo pulse samples before failsafe */
#define RC_LED_FREQUENCY 5UL /* In Hertz, not accurate, min=1, max=you will get a warning */
#define RC_THROTTLE_CH_OFFSET_PW 25 /* in microseconds. */
/********************************************************************************************************/
/* USER CONFIGURATION BLOCK END */
/********************************************************************************************************/
#endif //#ifndef SERVO2PPM_SETTINGS_H

View File

@ -1,4 +1,5 @@
FRAME 0
MAG_ENABLE 1
LOG_BITMASK 4095
RC1_MAX 2000.000000
RC1_MIN 1000.000000

View File

@ -9,7 +9,7 @@ testdir=os.path.dirname(os.path.realpath(__file__))
sys.path.insert(0, util.reltopdir('../pymavlink'))
import mavutil, mavwp
HOME_LOCATION='-35.362938,149.165085,584,270'
HOME=location(-35.362938,149.165085,584,270)
homeloc = None
num_wp = 0
@ -231,6 +231,11 @@ def fly_ArduCopter(viewerip=None):
'''
global expect_list, homeloc
hquad_cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%f,%f,%u,%u' % (
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
if viewerip:
hquad_cmd += ' --fgout=192.168.2.15:9123'
sil = util.start_SIL('ArduCopter', wipe=True)
mavproxy = util.start_MAVProxy_SIL('ArduCopter')
mavproxy.expect('Please Run Setup')
@ -239,7 +244,7 @@ def fly_ArduCopter(viewerip=None):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter')
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
@ -249,8 +254,11 @@ def fly_ArduCopter(viewerip=None):
# reboot with new parameters
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter')
options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
sil = util.start_SIL('ArduCopter', height=HOME.alt)
hquad = pexpect.spawn(hquad_cmd, logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad)
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
if viewerip:
options += ' --out=%s:14550' % viewerip
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
@ -264,19 +272,11 @@ def fly_ArduCopter(viewerip=None):
os.unlink(buildlog)
os.link(logfile, buildlog)
mavproxy.expect("Ready to FLY")
mavproxy.expect('Received [0-9]+ parameters')
mavproxy.expect("Ready to FLY")
util.expect_setup_callback(mavproxy, expect_callback)
# start hil_quad.py
cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%s' % HOME_LOCATION
if viewerip:
cmd += ' --fgout=192.168.2.15:9123'
hquad = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad)
hquad.expect('Starting at')
expect_list.extend([hquad, sil, mavproxy])
# get a mavlink connection going
@ -286,6 +286,7 @@ def fly_ArduCopter(viewerip=None):
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
failed = False

View File

@ -6,12 +6,15 @@ import pexpect, os, util, sys, shutil
import arducopter, arduplane
import optparse, fnmatch, time, glob, traceback
os.environ['PYTHONUNBUFFERED'] = '1'
os.putenv('TMPDIR', util.reltopdir('tmp'))
def get_default_params(atype):
'''get default parameters'''
sil = util.start_SIL(atype, wipe=True)
mavproxy = util.start_MAVProxy_SIL(atype)
print("Dumping defaults")
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
if idx == 0:
# we need to restart it after eeprom erase
@ -35,14 +38,22 @@ def dump_logs(atype):
logfile = util.reltopdir('../buildlogs/%s.flashlog' % atype)
log = open(logfile, mode='w')
mavproxy = util.start_MAVProxy_SIL(atype, setup=True, logfile=log)
print("navigating menus")
mavproxy.expect(']')
mavproxy.send("logs\n")
mavproxy.expect("logs enabled:")
mavproxy.expect("(\d+) logs")
numlogs = int(mavproxy.match.group(1))
lognums = []
i = mavproxy.expect(["No logs", "(\d+) logs"])
if i == 0:
numlogs = 0
else:
numlogs = int(mavproxy.match.group(1))
for i in range(numlogs):
mavproxy.expect("Log (\d+),")
lognums.append(int(mavproxy.match.group(1)))
mavproxy.expect("Log]")
for i in range(numlogs):
mavproxy.send("dump %u\n" % (i+1))
mavproxy.send("dump %u\n" % lognums[i])
mavproxy.expect("logs enabled:", timeout=400)
mavproxy.expect("Log]")
util.pexpect_close(mavproxy)
@ -150,7 +161,7 @@ def run_step(step):
return dump_logs('ArduCopter')
if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter()
return arducopter.fly_ArduCopter(viewerip=opts.viewerip)
if step == 'fly.ArduPlane':
if not opts.experimental:
@ -241,7 +252,8 @@ def run_tests(steps):
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
traceback.print_exc(file=sys.stdout)
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
pass
util.pexpect_close_all()
continue
results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
if not passed:

View File

@ -4,17 +4,21 @@ import util, pexpect, time, math
# messages. This keeps the output to stdout flowing
expect_list = []
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
def idle_hook(mav):
'''called when waiting for a mavlink message'''
global expect_list
# if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
# print(msg)
for p in expect_list:
try:
p.read_nonblocking(100, timeout=0)
except pexpect.TIMEOUT:
pass
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
# if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
# print(msg)
idle_hook(mav)
def expect_callback(e):
'''called when waiting for a expect pattern'''
global expect_list
@ -30,10 +34,11 @@ def expect_callback(e):
class location(object):
'''represent a GPS coordinate'''
def __init__(self, lat, lng, alt=0):
def __init__(self, lat, lng, alt=0, heading=0):
self.lat = lat
self.lng = lng
self.alt = alt
self.heading = heading
def __str__(self):
return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt)

View File

@ -44,7 +44,7 @@ def deltree(path):
def build_SIL(atype):
'''build desktop SIL'''
run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean hil",
run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean all",
dir=reltopdir(atype),
checkfail=True)
return True
@ -95,7 +95,7 @@ def pexpect_close_all():
for p in close_list[:]:
pexpect_close(p)
def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
def start_SIL(atype, valgrind=False, wipe=False, CLI=False, height=None):
'''launch a SIL instance'''
cmd=""
if valgrind and os.path.exists('/usr/bin/valgrind'):
@ -105,6 +105,8 @@ def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
cmd += ' -w'
if CLI:
cmd += ' -s'
if height is not None:
cmd += ' -H %u' % height
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
pexpect_autoclose(ret)
ret.expect('Waiting for connection')

25
Tools/scripts/build_all.sh Executable file
View File

@ -0,0 +1,25 @@
#!/bin/bash
# useful script to test all the different build types that we support.
# This helps when doing large merges
# Andrew Tridgell, November 2011
set -e
set -x
pushd ArduPlane
for b in all apm2 hil hilsensors; do
pwd
make clean
make $b
done
make -f ../libraries/Desktop/Makefile.desktop clean all
popd
pushd ArduCopter
for b in all apm2 hil; do
pwd
make clean
make $b
done
make -f ../libraries/Desktop/Makefile.desktop clean all
popd

View File

@ -33,6 +33,7 @@
*/
extern "C" {
// AVR LibC Includes
#include <inttypes.h>
@ -51,12 +52,21 @@ extern "C" {
//{
//}
// the apm2 hardware needs to check the state of the
// chip using a direct IO port
// On APM2 prerelease hw, the data ready port is hooked up to PE7, which
// is not available to the arduino digitalRead function.
#define BMP_DATA_READY() (_apm2_hardware?(PINE&0x80):digitalRead(BMP085_EOC))
// Public Methods //////////////////////////////////////////////////////////////
void APM_BMP085_Class::Init(int initialiseWireLib)
bool APM_BMP085_Class::Init(int initialiseWireLib, bool apm2_hardware)
{
byte buff[22];
int i = 0;
_apm2_hardware = apm2_hardware;
pinMode(BMP085_EOC, INPUT); // End Of Conversion (PC7) input
if( initialiseWireLib != 0 )
@ -68,7 +78,9 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
// We read the calibration data registers
Wire.beginTransmission(BMP085_ADDRESS);
Wire.send(0xAA);
Wire.endTransmission();
if (Wire.endTransmission() != 0) {
return false;
}
Wire.requestFrom(BMP085_ADDRESS, 22);
@ -77,6 +89,9 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
buff[i] = Wire.receive(); // receive one byte
i++;
}
if (i != 22) {
return false;
}
ac1 = ((int)buff[0] << 8) | buff[1];
ac2 = ((int)buff[2] << 8) | buff[3];
@ -93,6 +108,7 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
//Send a command to read Temp
Command_ReadTemp();
BMP085_State = 1;
return true;
}
/*
@ -103,14 +119,14 @@ uint8_t APM_BMP085_Class::Read()
uint8_t result = 0;
if (BMP085_State == 1){
if (digitalRead(BMP085_EOC)){
if (BMP_DATA_READY()) {
ReadTemp(); // On state 1 we read temp
BMP085_State++;
Command_ReadPress();
}
}else{
if (BMP085_State == 5){
if (digitalRead(BMP085_EOC)){
if (BMP_DATA_READY()){
ReadPress();
Calculate();
@ -119,7 +135,7 @@ uint8_t APM_BMP085_Class::Read()
result = 1; // New pressure reading
}
}else{
if (digitalRead(BMP085_EOC)){
if (BMP_DATA_READY()){
ReadPress();
Calculate();
BMP085_State++;
@ -138,13 +154,13 @@ uint8_t APM_BMP085_Class::Read()
uint8_t result = 0;
if (BMP085_State == 1){
if (digitalRead(BMP085_EOC)){
if (BMP_DATA_READY()){
BMP085_State = 2;
ReadTemp(); // On state 1 we read temp
Command_ReadPress();
}
}else{
if (digitalRead(BMP085_EOC)){
if (BMP_DATA_READY()){
BMP085_State = 1; // Start again from state = 1
ReadPress();
Calculate();
@ -310,4 +326,4 @@ void APM_BMP085_Class::Calculate()
x1 = (x1 * 3038) >> 16;
x2 = (-7357 * p) >> 16;
Press = p + ((x1 + x2 + 3791) >> 4);
}
}

View File

@ -1,8 +1,8 @@
#ifndef APM_BMP085_h
#define APM_BMP085_h
#define TEMP_FILTER_SIZE 2
#define PRESS_FILTER_SIZE 4
#define TEMP_FILTER_SIZE 4
#define PRESS_FILTER_SIZE 8
#include "APM_BMP085_hil.h"
@ -19,9 +19,10 @@ class APM_BMP085_Class
int32_t Press;
//int Altitude;
uint8_t oss;
bool _apm2_hardware;
//int32_t Press0; // Pressure at sea level
void Init(int initialiseWireLib = 1);
bool Init(int initialiseWireLib = 1, bool apm2_hardware=false);
uint8_t Read();
private:

View File

@ -15,7 +15,7 @@ APM_BMP085_HIL_Class::APM_BMP085_HIL_Class()
}
// Public Methods //////////////////////////////////////////////////////////////
void APM_BMP085_HIL_Class::Init(int initialiseWireLib)
void APM_BMP085_HIL_Class::Init(int initialiseWireLib, bool apm2_hardware)
{
BMP085_State=1;
}

View File

@ -13,9 +13,10 @@ class APM_BMP085_HIL_Class
int32_t Press;
//int Altitude;
uint8_t oss;
void Init(int initialiseWireLib = 1);
void Init(int initialiseWireLib = 1, bool apm2_hardware=false);
uint8_t Read();
void setHIL(float Temp, float Press);
int32_t _offset_press;
};
#endif

View File

@ -3,6 +3,7 @@
Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
*/
#include <FastSerial.h>
#include <Wire.h>
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
@ -10,12 +11,22 @@ APM_BMP085_Class APM_BMP085;
unsigned long timer;
FastSerialPort0(Serial);
#ifdef APM2_HARDWARE
static bool apm2_hardware = true;
#else
static bool apm2_hardware = false;
#endif
void setup()
{
Serial.begin(115200);
Serial.println("ArduPilot Mega BMP085 library test");
Serial.println("Initialising barometer..."); delay(100);
APM_BMP085.Init(); // APM ADC initialization
if (!APM_BMP085.Init(1, apm2_hardware)) {
Serial.println("Barometer initialisation FAILED\n");
}
Serial.println("initialisation complete."); delay(100);
delay(1000);
timer = millis();

View File

@ -1,2 +1,5 @@
BOARD = mega
include ../../../AP_Common/Arduino.mk
apm2:
make -f Makefile EXTRAFLAGS="-DAPM2_HARDWARE=1"

Some files were not shown because too many files have changed in this diff Show More