Browse Source

Work around quirkiness with ArduPilot and LOITER_* NaN handling on heading.

QGC4.4
Don Gagne 6 years ago
parent
commit
929d4210ec
  1. 30
      src/FirmwarePlugin/APM/MavCmdInfoCommon.json
  2. 22
      src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
  3. 33
      src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
  4. 6
      src/MissionManager/MavCmdInfoCommon.json

30
src/FirmwarePlugin/APM/MavCmdInfoCommon.json

@ -10,6 +10,36 @@ @@ -10,6 +10,36 @@
"paramRemove": "2"
},
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"specifiesCoordinate": false,

22
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json

@ -10,6 +10,28 @@ @@ -10,6 +10,28 @@
"paramRemove": "1,3,4"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "4"

33
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json

@ -10,39 +10,6 @@ @@ -10,39 +10,6 @@
"paramRemove": "2,3"
},
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"param4": {
"label": "Heading",
"units": "radians",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Heading",
"units": "radians",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Heading",
"units": "radians",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1"

6
src/MissionManager/MavCmdInfoCommon.json

@ -101,7 +101,8 @@ @@ -101,7 +101,8 @@
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
@ -128,7 +129,8 @@ @@ -128,7 +129,8 @@
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},

Loading…
Cancel
Save