Mission planner is asking home altitude whenever I add waypoint programmatically

Hello.

Below is my mission planner csharp plugin code.

this code add waypoint on planner screen well as I intended.

but, I wonder why there is always “you must have home altitude” screen.

I’m programmatically updating home point of my aircraft. could that be the reason?

I enter home altitude value as “0” and it worked in SITL, but I’m worrying about something I don’t know happen inside the program :

public void minuteToDigitWaypoints()
        {
            try
            {
                string input = "";
                InputBox.Show("Minutes -> Digits", "Input Format : 35-29.33333'S;129-35.99999'W", ref input);

                if (string.IsNullOrEmpty(input))
                {
                    MessageBox.Show("Nothing Entered");
                    return; // Exit if the input is empty or canceled
                }

                // Define the regular expression pattern to match the input format
                string pattern = @"^(\d{1,3})-(\d{1,2}\.\d+)'([NSns]);(\d{1,3})-(\d{1,2}\.\d+)'([EWew])$";

                Match match = Regex.Match(input, pattern);

                if (match.Success)
                {
                    double latitude = double.Parse(match.Groups[1].Value) + double.Parse(match.Groups[2].Value) / 60;
                    if ((match.Groups[3].Value == "S") || (match.Groups[3].Value == "s"))
                        latitude *= -1;

                    double longitude = double.Parse(match.Groups[4].Value) + double.Parse(match.Groups[5].Value) / 60;
                    if ((match.Groups[6].Value == "W") || (match.Groups[6].Value == "w"))
                        longitude *= -1;

                    string result = $"Original input: {input}\n\n" +
                        $"Converted coordinates:\nLatitude: {latitude}, Longitude: {longitude}";
                    Clipboard.SetText(result);
                    // Display the result in a new dialog box
                    MessageBox.Show(result + "\n\nabove contents was copied to clipboard.", "Conversion Results");
                    SaveResultToNotepad(result, " Minutes To Digits");

                    Host.AddWPtoList(MAVLink.MAV_CMD.WAYPOINT, 0, 0, 0, 0, longitude, latitude, 300);
                }
                else
                {
                    MessageBox.Show("Wrong Input. Input format : 35-29.33333'S;129-35.99999'W",
                        "Wrong Input format", MessageBoxButtons.OK, MessageBoxIcon.Warning);
                }
            }
            catch (Exception ex)
            {
                MessageBox.Show($"An error occurred: {ex.Message}", "Error", MessageBoxButtons.OK, MessageBoxIcon.Error);
            }
        }

The AddWpToList is closely entangled with the flight planner screen. And it does some cross-checks for valid inputs. However, the input checks are based on the contents of the FlighPlanner form. In this case, the ominous code is this :slight_smile:

                    bool pass = double.TryParse(TXT_homealt.Text, out result);

                    if (pass == false)
                    {
                        CustomMessageBox.Show("You must have a home altitude");
                        string homealt = "100";
                        if (DialogResult.Cancel == InputBox.Show("Home Alt", "Home Altitude", ref homealt))
                            return;
                        TXT_homealt.Text = homealt;
                    }

Which checks the content of the TXT_homealt textinput field. This is populated when added home location the FlightPlanner tab, but if you did not open the FlightPlanner and tried to add wp to it from a plugin, you will have an empty field.

The solution is to move either make sure that the FlightPlanner tab is opened at least once or fill out the field from the plugin.

Note, if you did not set the Home location ever (clean MP config) then home alt will not populated until you set a home location by hand. (Right clock on the map>set home location)

1 Like

Oh great, Thanks!!

The Mystery is solved, thanks to you.

Below is my C# home-update plugin code that I’m currently using. :

MAVLink.mavlink_command_long_t cmd = new MAVLink.mavlink_command_long_t
{
          target_system = mav.MAV.sysid,
          target_component = mav.MAV.compid,
          command = (ushort)MAVLink.MAV_CMD.DO_SET_HOME,
          param1 = 0,
          param5 = (float)ship_lat,
          param6 = (float)ship_lng,
          param7 = (float)0 //altitude.
};
if ((ship_sysid != 0) && (ship_compid != 0) && (is_home_updating_running))
{
          mav.sendPacket(cmd, mav.sysidcurrent, mav.compidcurrent);
          Console.WriteLine("Plugin : VTOL Home position updated.");
          Console.Write("To : ");
          Console.Write(ship_lat);
          Console.Write(" ");
          Console.WriteLine(ship_lng);
}

I Initially thought this code was sufficient for home updating, as I’ve been using this code for more than 2 months and it worked great.

However, after reading your answer, I began to question the completeness of my code.

it appears that I need to update “TXT_homealt.txt” whenever I change the home position, is that correct?

Could you provide any recommendations regarding my home-position updating code?

I apologize for bothering you, If I had a fast internet connection, I would study this by myself and explore into the mission planner code,

but currently I’m in south pacific with limited network connectivity.

and I believe it is good to share my code, I couldn’t find plugin questions although it is very useful.

I remember similar question was uploaded before. that question was asking how to input “minute-seconds” coordinates to mission planner.

this is very needed by ship because ship uses “minute-seconds” coordinates because it is easy to calculate.

1 knots is 1 miles per 1 hour, and it is same with latitude or longitude 1 minute.

so every ship uses minute-seconds unit, including cargo ships and fishing vessels.

actually my home update code is also for ships.

Your code is good. It is just the MP GUI complaining.
The Home location is updated anyway at arm, regardless of what you set in the MP GUI.
What you can do for make it foolproof is to use the getHomePositionAsync (or a getHomePosition, which calls the async one, but obsolete) and check back that the sent coordinates are accepted by the vehicle.

1 Like

Thanks to you, I could add the line to my home point updating code.

I added this line : "Host.MainForm.FlightPlanner.TXT_homealt.Text = “0"”
at first I was worrying about handling UI at Plugin thread, but nothing happend when I handled UI.

it worked great on SITL.

below is my updated code :

MAVLink.mavlink_command_long_t cmd = new MAVLink.mavlink_command_long_t
 {
        target_system = mav.MAV.sysid,
        target_component = mav.MAV.compid,
        command = (ushort)MAVLink.MAV_CMD.DO_SET_HOME,
        param1 = 0,
        param5 = (float)ship_lat,
        param6 = (float)ship_lng,
        param7 = (float)0 //altitude.
  };

  if ((ship_sysid != 0) && (ship_compid != 0) && (is_home_updating_running))
  {
        mav.sendPacket(cmd, mav.sysidcurrent, mav.compidcurrent);
        Console.WriteLine("Plugin : VTOL Home position updated.");
        Console.Write("To : ");
        Console.Write(ship_lat);
        Console.Write(" ");
        Console.WriteLine(ship_lng);
        Host.MainForm.FlightPlanner.TXT_homealt.Text = "0";
   }