Skip to content

Commit

Permalink
Fix for ISSUE ArduPilot#2714, Radio Calibration Screen reverse CB doe…
Browse files Browse the repository at this point in the history
…s not honor RCMAP setting.
  • Loading branch information
EosBandi authored and meee1 committed Dec 12, 2021
1 parent e3d3fc6 commit 4aefe60
Show file tree
Hide file tree
Showing 2 changed files with 55 additions and 49 deletions.
80 changes: 40 additions & 40 deletions GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

24 changes: 15 additions & 9 deletions GCSViews/ConfigurationView/ConfigRadioInput.cs
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,12 @@ public void Activate()
BAR15.DataBindings.Add(new Binding("Value", currentStateBindingSource, "ch15in", true));
BAR16.DataBindings.Add(new Binding("Value", currentStateBindingSource, "ch16in", true));

//Add channel to pitch/roll/throttle/yaw bars labels
BARroll.Label = BARroll.Label + " (ch" + chroll.ToString() + ")";
BARpitch.Label = BARpitch.Label + " (ch" + chpitch.ToString() + ")";
BARthrottle.Label = BARthrottle.Label + " (ch" + chthro.ToString() + ")";
BARyaw.Label = BARyaw.Label + " (ch" + chyaw.ToString() + ")";

try
{
// force this screen to work
Expand All @@ -131,16 +137,16 @@ public void Activate()
}

// this controls the direction of the output, not the input.
CHK_revch1.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC1_REV", "RC1_REVERSED" },
CHK_revroll.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC" + chroll + "_REV", "RC" + chroll + "_REVERSED" },
MainV2.comPort.MAV.param);
CHK_revch2.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC2_REV", "RC2_REVERSED" },
CHK_revpitch.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC" + chpitch + "_REV", "RC" + chpitch + "_REVERSED" },
MainV2.comPort.MAV.param);
CHK_revch3.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC3_REV", "RC3_REVERSED" },
CHK_revthr.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC" + chthro + "_REV", "RC" + chthro + "_REVERSED" },
MainV2.comPort.MAV.param);
CHK_revch4.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC4_REV", "RC4_REVERSED" },
CHK_revyaw.setup(new double[] { -1, 1 }, new double[] { 1, 0 }, new string[] { "RC" + chyaw + "_REV", "RC" + chyaw + "_REVERSED" },
MainV2.comPort.MAV.param);

if(MainV2.comPort.MAV.param["RC"+ chroll + "_REVERSED"]?.Value == 1)
if (MainV2.comPort.MAV.param["RC"+ chroll + "_REVERSED"]?.Value == 1)
{
reverseChannel(true, BARroll);
}
Expand All @@ -161,10 +167,10 @@ public void Activate()
// run after to ensure they are disabled on copter
if (MainV2.comPort.MAV.cs.firmware == Firmwares.ArduCopter2)
{
CHK_revch1.Visible = false;
CHK_revch2.Visible = false;
CHK_revch3.Visible = false;
CHK_revch4.Visible = false;
CHK_revroll.Visible = false;
CHK_revpitch.Visible = false;
CHK_revthr.Visible = false;
CHK_revyaw.Visible = false;
}

startup = false;
Expand Down

0 comments on commit 4aefe60

Please sign in to comment.