Skip to content

Update ConfigureArducopter and FlightPlanner to accomodate new param names and units/scales#3685

Open
EosBandi wants to merge 9 commits intoArduPilot:masterfrom
EosBandi:Copter4.7updates
Open

Update ConfigureArducopter and FlightPlanner to accomodate new param names and units/scales#3685
EosBandi wants to merge 9 commits intoArduPilot:masterfrom
EosBandi:Copter4.7updates

Conversation

@EosBandi
Copy link
Copy Markdown
Collaborator

Support for ArduCopter 4.7 Parameter Changes:

  • Adds class paramchanges47 to utilities, mapping old parameter names to new ones, describes unit changes, and adds helper methods to look up mappings and warnings.
  • Updated parameter setup calls in ConfigArducopter.cs
  • Updated FlightPlanner to handle WP_RADIUS_M
  • Adds a warning in the ConfigArducopter to warn users about parameter renames and unit changes when editing parameters affected by the 4.7 update.

Note: Changes in ConfigArducopter.Designer are :

  • Adding a label to display a warning
  • add event handler to all NumUpDown controls' Enter event.

@EosBandi
Copy link
Copy Markdown
Collaborator Author

These are the obvoius ones, still combing through the full code for possible impacts....

@rmackay9
Copy link
Copy Markdown
Contributor

@EosBandi thank you so much!!

Comment thread GCSViews/ConfigurationView/ConfigArducopter.cs
@meee1
Copy link
Copy Markdown
Collaborator

meee1 commented Apr 13, 2026

for those that looked over this, are we all happy?

{ "Q_LOIT_BRK_ACC_M", "Q_LOIT_BRK_ACCEL → Q_LOIT_BRK_ACC_M: units changed from cm/s/s to m/s/s" },
{ "Q_LOIT_BRK_JRK_M", "Q_LOIT_BRK_JERK → Q_LOIT_BRK_JRK_M: units changed from cm/s/s/s to m/s/s/s" },
// Q_PILOT (Plane QuadPlane)
{ "Q_PILOT_ACCEL_Z", "Q_PILOT_ACCEL_Z → Q_PILOT_ACCEL_Z: units changed from cm/s/s to m/s/s" },
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry, we can remove these lines because the parameters were not changed between 4.6 and 4.7. This mistake actually originates from my incorrect release notes, sorry!

`
{ "Q_PILOT_ACCEL_Z", "Q_PILOT_ACCEL_Z → Q_PILOT_ACCEL_Z: units changed from cm/s/s to m/s/s" },
{ "Q_PILOT_SPD_UP", "Q_PILOT_SPEED_UP → Q_PILOT_SPD_UP: units changed from cm/s to m/s" },
{ "Q_PILOT_SPD_DN", "Q_PILOT_SPEED_DN → Q_PILOT_SPD_DN: units changed from cm/s to m/s" },
{ "Q_PILOT_TKO_ALT_M", "Q_PILOT_TKOFF_ALT → Q_PILOT_TKO_ALT_M: units changed from cm to m" },

`

@meee1 meee1 requested a review from Copilot April 18, 2026 00:01
Copy link
Copy Markdown

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Note

Copilot was unable to run its full agentic suite in this review.

Updates Mission Planner UI/configuration logic to handle ArduCopter 4.7 parameter renames and unit/scale changes, including adding a central mapping helper and extending several views to read/write the newer parameters.

Changes:

  • Add paramchanges47 utility mapping old↔new 4.7 parameter names and unit-change descriptions.
  • Update multiple UI/config flows to prefer new 4.7 parameters (with fallback to legacy names) and apply unit conversions.
  • Add UI warning behavior when editing parameters affected by 4.7 renames/unit changes.

Reviewed changes

Copilot reviewed 9 out of 10 changed files in this pull request and generated 8 comments.

Show a summary per file
File Description
plugins/FaceMap/FaceMapUI.cs Use WP_SPD fallback and ensure speed is in m/s for DO_CHANGE_SPEED.
Swarm/WaypointLeader/DroneGroup.cs Update RTL/WPNAV accel parameter sets to support 4.7 names/units.
Grid/GridUI.cs Same WP_SPD fallback logic as FaceMap for speed changes.
GCSViews/FlightPlanner.cs Support WP_RADIUS_M and 4.7 WPNAV speed/accel param changes with unit conversions.
GCSViews/ConfigurationView/ConfigInitialParams.cs Handle ATC accel param rename/unit scaling and update user guidance text.
GCSViews/ConfigurationView/ConfigArducopter.cs Expand supported param aliases and add enter-warning for 4.7 param changes.
GCSViews/ConfigurationView/ConfigAC_Fence.cs Prefer RTL_ALT_M when present and adjust displayed/default scaling.
ExtLibs/Utilities/paramchanges47.cs New mapping helper for 4.7 param renames and warnings.

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment on lines +216 to +220
// rtl at current alt
if (MAV.param.ContainsKey("RTL_ALT"))
MAV.parent.setParam(MAV.sysid, MAV.compid, "RTL_ALT", 0);
else if (MAV.param.ContainsKey("RTL_ALT_M"))
MAV.parent.setParam(MAV.sysid, MAV.compid, "RTL_ALT_M", 0);
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This changes behavior from explicitly fetching parameters (GetParam) to relying on MAV.param.ContainsKey(...). If the param dictionary is not populated/complete at this point, these blocks will silently skip setting RTL altitude / accel (no attempt to set or to fetch). Fix by either (a) fetching the relevant param(s) before checking (GetParam for both possible names), or (b) attempting setParam for the preferred name and falling back to the alternate name on failure (with a targeted exception check), rather than gating the write on ContainsKey.

Copilot uses AI. Check for mistakes.
Comment on lines +227 to +231
// set accel to default
if (MAV.param.ContainsKey("WPNAV_ACCEL"))
MAV.parent.setParam(MAV.sysid, MAV.compid, "WPNAV_ACCEL", 100); // 100 cm/s/s
else if (MAV.param.ContainsKey("WP_ACC"))
MAV.parent.setParam(MAV.sysid, MAV.compid, "WP_ACC", 1); // 1 m/s/s
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This changes behavior from explicitly fetching parameters (GetParam) to relying on MAV.param.ContainsKey(...). If the param dictionary is not populated/complete at this point, these blocks will silently skip setting RTL altitude / accel (no attempt to set or to fetch). Fix by either (a) fetching the relevant param(s) before checking (GetParam for both possible names), or (b) attempting setParam for the preferred name and falling back to the alternate name on failure (with a targeted exception check), rather than gating the write on ContainsKey.

Copilot uses AI. Check for mistakes.
Comment thread GCSViews/FlightPlanner.cs
Comment on lines +6297 to 6307
// use brute force, for all three possible params

// m
port.setParam("WP_RADIUS", float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist);

// m
port.setParam("WP_RADIUS_M", float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist);

// cm's
port.setParam("WPNAV_RADIUS", float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist * 100.0);

Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unconditionally writing all three parameters can generate avoidable MAVLink PARAM_SET failures/noise (and potentially slow down or confuse users) on firmwares that only support one of these names. Prefer setting only the parameter(s) that exist on the connected vehicle (e.g., check the param dictionary for supported keys), or wrap each setParam in targeted error handling and only attempt fallbacks if the first write fails.

Suggested change
// use brute force, for all three possible params
// m
port.setParam("WP_RADIUS", float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist);
// m
port.setParam("WP_RADIUS_M", float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist);
// cm's
port.setParam("WPNAV_RADIUS", float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist * 100.0);
var wpRadiusMeters = float.Parse(TXT_WPRad.Text) / CurrentState.multiplierdist;
var wpRadiusCentimeters = wpRadiusMeters * 100.0f;
// Try the supported waypoint-radius parameter name for the connected firmware,
// only falling back to alternatives if the previous write fails.
Exception wpRadiusSetException = null;
try
{
// m
port.setParam("WP_RADIUS", wpRadiusMeters);
}
catch (Exception ex1)
{
wpRadiusSetException = ex1;
try
{
// m
port.setParam("WP_RADIUS_M", wpRadiusMeters);
wpRadiusSetException = null;
}
catch (Exception ex2)
{
wpRadiusSetException = ex2;
try
{
// cm's
port.setParam("WPNAV_RADIUS", wpRadiusCentimeters);
wpRadiusSetException = null;
}
catch (Exception ex3)
{
wpRadiusSetException = ex3;
}
}
}
if (wpRadiusSetException != null)
throw wpRadiusSetException;

Copilot uses AI. Check for mistakes.
Comment on lines +484 to +501
private void OnEnter_NumUpDown(object sender, EventArgs e)
{
// show unit change warning for Copter 4.7 renamed parameters
if (VersionDetection.GetVersion(MainV2.comPort.MAV.VersionString) >= new Version(4, 7)
&& sender is MavlinkNumericUpDown mnud)
{
var warning = paramchanges47.changedByNewParamWarning(mnud.ParamName);
if (warning != null)
{
lblUnitWarning.Text = "Change in 4.7: " + warning;
lblUnitWarning.Visible = true;
lblUnitWarning.ForeColor = Color.Red;
return;
}
}

lblUnitWarning.Visible = false;
}
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The warning lookup only checks changedByNewParamWarning(mnud.ParamName). If the control is currently bound to a legacy (pre-4.7) parameter name (which is common since setup(...) lists both old/new aliases), mnud.ParamName may be the old name and no warning will display. Fix by supporting both directions: if no warning is found, first map old→new via changedByOldParam(mnud.ParamName) and then retrieve the warning for the mapped new name (or add a utility method that accepts either old or new).

Copilot uses AI. Check for mistakes.
Comment on lines +133 to +137
// reverse index: old param name → new param name
private static readonly Dictionary<string, string> _oldToNew = _byNewParam
.ToDictionary(
kv => kv.Value.Substring(0, kv.Value.IndexOf(" →")),
kv => kv.Key);
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Building _oldToNew by parsing a human-readable string is brittle: if any entry format changes (missing ' →', different spacing, etc.) this will throw during type initialization and break the app at startup. Consider storing structured data (e.g., a small record/class with OldName, NewName, WarningText) and deriving both dictionaries from explicit fields; at minimum guard IndexOf results and fail gracefully.

Copilot uses AI. Check for mistakes.
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

New public API types in C# should follow PascalCase naming. Consider renaming paramchanges47 to ParamChanges47 (and similarly PascalCase for its public methods) to match standard .NET conventions. Also, using System.Text; is unused in this file and can be removed.

Copilot uses AI. Check for mistakes.

namespace MissionPlanner.Utilities
{
public class paramchanges47
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

New public API types in C# should follow PascalCase naming. Consider renaming paramchanges47 to ParamChanges47 (and similarly PascalCase for its public methods) to match standard .NET conventions. Also, using System.Text; is unused in this file and can be removed.

Copilot uses AI. Check for mistakes.
if (paramCompareForm.DialogResult == DialogResult.OK)
{
CustomMessageBox.Show("Initial Parameters succesfully updated.\r\nCheck parameters before flight!\r\n\r\nAfter test flight :\r\n\tSet ATC_THR_MIX_MAN to 0.5\r\n\tSet PSC_ACCZ_P to MOT_THST_HOVER\r\n\tSet PSC_ACCZ_I to 2*MOT_THST_HOVER\r\n\r\nHappy flying!", "Initial parameter calculator");
CustomMessageBox.Show("Initial Parameters succesfully updated.\r\nCheck parameters before flight!\r\n\r\nAfter test flight :\r\n\tSet ATC_THR_MIX_MAN to 0.5\r\n\tSet PSC_ACCZ_P/PSC_D_ACC_P to MOT_THST_HOVER\r\n\tSet PSC_ACCZ_I/PSC_D_ACC_I to 2*MOT_THST_HOVER\r\n\r\nHappy flying!", "Initial parameter calculator");
Copy link

Copilot AI Apr 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Correct spelling: change 'succesfully' to 'successfully' in the user-facing message.

Suggested change
CustomMessageBox.Show("Initial Parameters succesfully updated.\r\nCheck parameters before flight!\r\n\r\nAfter test flight :\r\n\tSet ATC_THR_MIX_MAN to 0.5\r\n\tSet PSC_ACCZ_P/PSC_D_ACC_P to MOT_THST_HOVER\r\n\tSet PSC_ACCZ_I/PSC_D_ACC_I to 2*MOT_THST_HOVER\r\n\r\nHappy flying!", "Initial parameter calculator");
CustomMessageBox.Show("Initial Parameters successfully updated.\r\nCheck parameters before flight!\r\n\r\nAfter test flight :\r\n\tSet ATC_THR_MIX_MAN to 0.5\r\n\tSet PSC_ACCZ_P/PSC_D_ACC_P to MOT_THST_HOVER\r\n\tSet PSC_ACCZ_I/PSC_D_ACC_I to 2*MOT_THST_HOVER\r\n\r\nHappy flying!", "Initial parameter calculator");

Copilot uses AI. Check for mistakes.
@rmackay9
Copy link
Copy Markdown
Contributor

rmackay9 commented Apr 21, 2026

@EosBandi, no huge pressure of course but could you update this PR when you get a chance? I'm just keen to clear up our AP 4.7 issues list!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

5 participants