diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde
index 6cacb73e86..674c096e25 100644
--- a/ArduPlane/radio.pde
+++ b/ArduPlane/radio.pde
@@ -24,10 +24,6 @@ static void init_rc_in()
//set auxiliary ranges
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
- G_RC_AUX(k_flap)->set_range(0,100);
- G_RC_AUX(k_flap_auto)->set_range(0,100);
- G_RC_AUX(k_aileron)->set_angle(SERVO_MAX);
- G_RC_AUX(k_flaperon)->set_range(0,100);
}
static void init_rc_out()
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index 6ac38ed914..ddfdd3e8d6 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -232,7 +232,6 @@
UserControl
-
Component
@@ -302,7 +301,6 @@
ElevationProfile.cs
-
Component
@@ -338,6 +336,7 @@
Splash.cs
+
Form
@@ -374,6 +373,7 @@
Firmware.cs
+ Designer
FlightData.cs
@@ -424,6 +424,7 @@
Firmware.cs
Always
+ Designer
FlightData.cs
diff --git a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs b/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs
index 99660f265f..94e3281f84 100644
--- a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs
+++ b/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs
@@ -6,7 +6,6 @@ using System.IO.Ports;
using System.Threading;
using System.Net; // dns, ip address
using System.Net.Sockets; // tcplistner
-using SerialProxy;
namespace System.IO.Ports
{
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
index 9dba66f3d1..8758775aac 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
@@ -257,6 +257,8 @@ namespace ArdupilotMega.GCSViews
internal void processToScreen()
{
+
+
Params.Rows.Clear();
// process hashdefines and update display
@@ -541,7 +543,10 @@ namespace ArdupilotMega.GCSViews
private void BUT_writePIDS_Click(object sender, EventArgs e)
{
- foreach (string value in changes.Keys)
+
+ Hashtable temp = (Hashtable)changes.Clone();
+
+ foreach (string value in temp.Keys)
{
try
{
@@ -566,6 +571,7 @@ namespace ArdupilotMega.GCSViews
if (row.Cells[0].Value.ToString() == value)
{
row.Cells[1].Style.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+ changes.Remove(value);
break;
}
}
@@ -575,8 +581,6 @@ namespace ArdupilotMega.GCSViews
}
catch { MessageBox.Show("Set " + value + " Failed"); }
}
-
- changes.Clear();
}
const float rad2deg = (float)(180 / Math.PI);
@@ -600,9 +604,11 @@ namespace ArdupilotMega.GCSViews
MainV2.fixtheme(temp);
- TabSetup.Controls.Clear();
+ temp.ShowDialog();
- TabSetup.Controls.Add(temp.Controls[0]);
+ startup = true;
+ processToScreen();
+ startup = false;
}
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
index 1e7c2544c7..15f3a849f7 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
@@ -519,13 +519,18 @@ namespace ArdupilotMega.GCSViews
}
catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.Message); return; }
+ UploadFlash(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex", board);
+ }
+
+ void UploadFlash(string filename, string board)
+ {
byte[] FLASH = new byte[1];
StreamReader sr = null;
try
{
lbl_status.Text = "Reading Hex File";
this.Refresh();
- sr = new StreamReader(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex");
+ sr = new StreamReader(filename);
FLASH = readIntelHEXv2(sr);
sr.Close();
Console.WriteLine("\n\nSize: {0}\n\n", FLASH.Length);
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx
index 95f999f7a7..7283c0a474 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx
@@ -343,16 +343,16 @@
NoControl
- 101, 165
+ 113, 167
- 79, 13
+ 56, 13
8
- ArduPilot Mega
+ ArduPlane
label1
@@ -403,16 +403,16 @@
NoControl
- 57, 362
+ 74, 361
- 168, 13
+ 142, 13
10
- ArduPilot Mega (Xplane simulator)
+ ArduPlane (Xplane simulator)
label3
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
index 21732c373e..e144fa180a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
@@ -347,7 +347,7 @@ namespace ArdupilotMega.GCSViews
{
TXT_mouselat.Text = lat.ToString();
TXT_mouselong.Text = lng.ToString();
- TXT_mousealt.Text = alt.ToString();
+ TXT_mousealt.Text = srtm.getAltitude(lat, lng).ToString("0");
try
{
diff --git a/Tools/ArdupilotMegaPlanner/HUD.cs b/Tools/ArdupilotMegaPlanner/HUD.cs
index b4e8e178f4..b95cd51577 100644
--- a/Tools/ArdupilotMegaPlanner/HUD.cs
+++ b/Tools/ArdupilotMegaPlanner/HUD.cs
@@ -236,7 +236,7 @@ System.ComponentModel.Category("Values")]
{
//Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds);
//e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
- return;
+ //return;
}
starttime = DateTime.Now;
@@ -1365,6 +1365,18 @@ System.ComponentModel.Category("Values")]
charbitmaps = new Bitmap[charbitmaps.Length];
+ try
+ {
+
+ foreach (int texid in charbitmaptexid)
+ {
+ if (texid != 0)
+ GL.DeleteTexture(texid);
+ }
+
+ }
+ catch { }
+
GC.Collect();
try
diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs
index e47cb2c35d..e51d159de0 100644
--- a/Tools/ArdupilotMegaPlanner/Log.cs
+++ b/Tools/ArdupilotMegaPlanner/Log.cs
@@ -366,45 +366,6 @@ namespace ArdupilotMega
}
}
- private byte[] readline(NetSerial comport)
- {
- byte[] temp = new byte[1024];
- int count = 0;
- int timeout = 0;
-
- while (timeout <= 100)
- {
- if (!comport.IsOpen) { break; }
- if (comport.BytesToRead > 0)
- {
- byte letter = (byte)comport.ReadByte();
-
- temp[count] = letter;
-
- if (letter == '\n') // normal line
- {
- break;
- }
-
-
- count++;
- if (count == temp.Length)
- break;
- timeout = 0;
- } else {
- timeout++;
- System.Threading.Thread.Sleep(5);
- }
- }
- if (timeout >= 100) {
- Console.WriteLine("readline timeout");
- }
-
- Array.Resize(ref temp, count + 1);
-
- return temp;
- }
-
List modelist = new List();
List[] position = new List[200];
int positionindex = 0;
diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs
index 0c26ebb6cd..242b2818aa 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs
@@ -951,6 +951,8 @@ namespace ArdupilotMega
req.seq = index;
+ //Console.WriteLine("getwp req "+ DateTime.Now.Millisecond);
+
// request
generatePacket(MAVLINK_MSG_ID_WAYPOINT_REQUEST, req);
@@ -972,11 +974,14 @@ namespace ArdupilotMega
MainV2.givecomport = false;
throw new Exception("Timeout on read - getWP");
}
+ //Console.WriteLine("getwp read " + DateTime.Now.Millisecond);
byte[] buffer = readPacket();
+ //Console.WriteLine("getwp readend " + DateTime.Now.Millisecond);
if (buffer.Length > 5)
{
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT)
{
+ //Console.WriteLine("getwp ans " + DateTime.Now.Millisecond);
__mavlink_waypoint_t wp = new __mavlink_waypoint_t();
object temp = (object)wp;
@@ -1070,7 +1075,7 @@ namespace ArdupilotMega
}
else
{
- //Console.WriteLine(DateTime.Now + " PC getwp " + buffer[5]);
+ Console.WriteLine(DateTime.Now + " PC getwp " + buffer[5]);
}
}
}
@@ -1455,16 +1460,18 @@ namespace ArdupilotMega
else
{
int to = 0;
- while (BaseStream.BytesToRead < length)
+ while (BaseStream.BytesToRead < (length - 4))
{
if (to > 1000)
{
Console.WriteLine("MAVLINK: wait time out btr {0} len {1}", BaseStream.BytesToRead, length);
break;
}
- System.Threading.Thread.Sleep(2);
- System.Windows.Forms.Application.DoEvents();
+ System.Threading.Thread.Sleep(1);
+ //System.Windows.Forms.Application.DoEvents();
to++;
+
+ //Console.WriteLine("data " + 0 + " " + length + " aval " + BaseStream.BytesToRead);
}
int read = BaseStream.Read(temp, 6, length - 4);
}
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 48dac31e32..451e8acea8 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -76,6 +76,8 @@ namespace ArdupilotMega
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
+ srtm.datadirectory = @"C:\srtm";
+
var t = Type.GetType("Mono.Runtime");
MAC = (t != null);
diff --git a/Tools/ArdupilotMegaPlanner/MyButton.cs b/Tools/ArdupilotMegaPlanner/MyButton.cs
index 12508be1f7..11bf6cd531 100644
--- a/Tools/ArdupilotMegaPlanner/MyButton.cs
+++ b/Tools/ArdupilotMegaPlanner/MyButton.cs
@@ -50,7 +50,7 @@ namespace ArdupilotMega
if (!this.Enabled)
{
- SolidBrush brush = new SolidBrush(Color.FromArgb(200, 0x2b, 0x3a, 0x03));
+ SolidBrush brush = new SolidBrush(Color.FromArgb(150, 0x2b, 0x3a, 0x03));
gr.FillRectangle(brush, 0, 0, this.Width, this.Height);
}
diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
index 25abe98b99..d4f74b5646 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
+++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
@@ -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.67")]
+[assembly: AssemblyFileVersion("1.0.68")]
[assembly: NeutralResourcesLanguageAttribute("")]
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
index 53279ab634..17c296b914 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
@@ -231,7 +231,6 @@ namespace ArdupilotMega.Setup
MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, oldrc);
- MainV2.comPort.param = MainV2.comPort.getParamList();
if (Configuration != null)
{
Configuration.startup = true;
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Firmware.resx b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Firmware.resx
index 95f999f7a7..7283c0a474 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Firmware.resx
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/Firmware.resx
@@ -343,16 +343,16 @@
NoControl
- 101, 165
+ 113, 167
- 79, 13
+ 56, 13
8
- ArduPilot Mega
+ ArduPlane
label1
@@ -403,16 +403,16 @@
NoControl
- 57, 362
+ 74, 361
- 168, 13
+ 142, 13
10
- ArduPilot Mega (Xplane simulator)
+ ArduPlane (Xplane simulator)
label3
diff --git a/Tools/ArdupilotMegaPlanner/srtm.cs b/Tools/ArdupilotMegaPlanner/srtm.cs
new file mode 100644
index 0000000000..e11c6ecb9b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/srtm.cs
@@ -0,0 +1,76 @@
+using System;
+using System.Collections.Generic;
+using System.Linq;
+using System.Text;
+using System.IO;
+
+namespace ArdupilotMega
+{
+ class srtm
+ {
+ public static string datadirectory;
+
+ public static int getAltitude(double lat, double lng)
+ {
+ short alt = -32768;
+
+ lat += 0.0008;
+ //lng += 0.0008;
+
+ int x = (int)Math.Floor(lng);
+ int y = (int)Math.Floor(lat);
+
+ string ns;
+ if (y > 0)
+ ns = "N";
+ else
+ ns = "S";
+
+ string ew;
+ if (x > 0)
+ ew = "E";
+ else
+ ew = "W";
+
+ string filename = ns+ Math.Abs(y).ToString("00")+ew+ Math.Abs(x).ToString("000")+".hgt";
+
+ if (!File.Exists(datadirectory + Path.DirectorySeparatorChar + filename))
+ {
+ return alt;
+ }
+
+ FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open,FileAccess.Read);
+
+ float posx = 0;
+ float row = 0;
+
+ if (fs.Length <= (1201 * 1201 * 2)) {
+ posx = (int)(((float)(lng - x)) * (1201 * 2));
+ row = (int)(((float)(lat - y)) * 1201) * (1201 * 2);
+ row = (1201 * 1201 * 2) - row;
+ } else {
+ posx = (int)(((float)(lng - x)) * (3601 * 2));
+ row = (int)(((float)(lat - y)) * 3601) * (3601 * 2);
+ row = (3601 * 3601 * 2) - row;
+ }
+
+ if (posx % 2 == 1)
+ {
+ posx--;
+ }
+
+ //Console.WriteLine(filename + " row " + row + " posx" + posx);
+
+ byte[] data = new byte[2];
+
+ fs.Seek((int)(row + posx), SeekOrigin.Begin);
+ fs.Read(data, 0, data.Length);
+
+ Array.Reverse(data);
+
+ alt = BitConverter.ToInt16(data,0);
+
+ return alt;
+ }
+ }
+}
diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp
index 18b35ea05e..1ff7b45326 100644
--- a/libraries/RC_Channel/RC_Channel_aux.cpp
+++ b/libraries/RC_Channel/RC_Channel_aux.cpp
@@ -47,4 +47,9 @@ void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Ch
g_rc_function[aux_servo_function[CH_6]] = rc_6;
g_rc_function[aux_servo_function[CH_7]] = rc_7;
g_rc_function[aux_servo_function[CH_8]] = rc_8;
+
+ G_RC_AUX(k_flap)->set_range(0,100);
+ G_RC_AUX(k_flap_auto)->set_range(0,100);
+ G_RC_AUX(k_aileron)->set_angle(4500);
+ G_RC_AUX(k_flaperon)->set_range(0,100);
}
diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h
index 556ffa6c3b..7e091bf18f 100644
--- a/libraries/RC_Channel/RC_Channel_aux.h
+++ b/libraries/RC_Channel/RC_Channel_aux.h
@@ -14,7 +14,6 @@
/// @class RC_Channel_aux
/// @brief Object managing one aux. RC channel (CH5-8), with information about its function
-/// Also contains physical min,max angular deflection, to allow calibrating open-loop servo movements
class RC_Channel_aux : public RC_Channel{
public:
/// Constructor
@@ -24,9 +23,7 @@ public:
///
RC_Channel_aux(AP_Var::Key key, const prog_char_t *name) :
RC_Channel(key, name),
- function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0), // suppress name if group has no name
- angle_min (&_group, 5, -4500, name ? PSTR("ANGLE_MIN") : 0), // assume -45 degrees min deflection
- angle_max (&_group, 6, 4500, name ? PSTR("ANGLE_MAX") : 0) // assume 45 degrees max deflection
+ function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0) // suppress name if group has no name
{}
typedef enum
@@ -41,8 +38,6 @@ public:
} Aux_servo_function_t;
AP_Int8 function; // 0=disabled, 1=manual, 2=flap, 3=flap auto, 4=aileron, 5=flaperon, 6=mount yaw (pan), 7=mount pitch (tilt), 8=mount roll, 9=camera trigger, 10=camera open, 11=egg drop
- AP_Int16 angle_min; // min angle limit of actuated surface in 0.01 degree units
- AP_Int16 angle_max; // max angle limit of actuated surface in 0.01 degree units
void output_ch(unsigned char ch_nr); // map a function to a servo channel and output it