Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
ed8b6aa5
Commit
ed8b6aa5
authored
Apr 25, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #3248 from dagar/master
update fixed wing cmd default values
parents
86ee86a2
82140c8d
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
335 additions
and
6 deletions
+335
-6
MavCmdInfoFixedWing.json
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
+162
-1
MavCmdInfoFixedWing.json
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
+162
-1
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+1
-1
MissionController.cc
src/MissionManager/MissionController.cc
+10
-3
No files found.
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
View file @
ed8b6aa5
{
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
16
,
"rawName"
:
"MAV_CMD_NAV_WAYPOINT"
,
"friendlyName"
:
"Waypoint"
,
"description"
:
"Travel to a position in 3D space."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"seconds"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
17
,
"rawName"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"friendlyName"
:
"Loiter"
,
"description"
:
"Travel to a position and Loiter around the specified radius indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
100
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
18
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"friendlyName"
:
"Loiter (turns)"
,
"description"
:
"Travel to a position and Loiter around the specified radius for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
100
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
19
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"friendlyName"
:
"Loiter (time)"
,
"description"
:
"Travel to a position and Loiter around the specified radius for a number of seconds."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Seconds:"
,
"units"
:
"seconds"
,
"default"
:
30
,
"decimalPlaces"
:
1
},
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
100
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
21
,
"rawName"
:
"MAV_CMD_NAV_LAND"
,
"friendlyName"
:
"Land"
,
"description"
:
"Land vehicle at the specified location."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Abort Alt:"
,
"units"
:
"meters"
,
"default"
:
25
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"radians"
,
"default"
:
0
,
"decimalPlaces"
:
2
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
0
,
"decimalPlaces"
:
1
}
},
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground and travel towards the specified position."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Pitch:"
,
"units"
:
"degrees"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"radians"
,
"default"
:
0
,
"decimalPlaces"
:
1
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
25
,
"decimalPlaces"
:
0
}
},
{
"id"
:
206
,
"rawName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST"
,
"friendlyName"
:
"Camera trigger distance"
,
"description"
:
"Set camera trigger distance."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Distance:"
,
"default"
:
25
,
"units"
:
"meters"
,
"decimalPlaces"
:
1
}
}
]
}
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
View file @
ed8b6aa5
{
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
16
,
"rawName"
:
"MAV_CMD_NAV_WAYPOINT"
,
"friendlyName"
:
"Waypoint"
,
"description"
:
"Travel to a position in 3D space."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"seconds"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
17
,
"rawName"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"friendlyName"
:
"Loiter"
,
"description"
:
"Travel to a position and Loiter around the specified radius indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
100
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
18
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"friendlyName"
:
"Loiter (turns)"
,
"description"
:
"Travel to a position and Loiter around the specified radius for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
100
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
19
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"friendlyName"
:
"Loiter (time)"
,
"description"
:
"Travel to a position and Loiter around the specified radius for a number of seconds."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Seconds:"
,
"units"
:
"seconds"
,
"default"
:
30
,
"decimalPlaces"
:
1
},
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
100
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
},
{
"id"
:
21
,
"rawName"
:
"MAV_CMD_NAV_LAND"
,
"friendlyName"
:
"Land"
,
"description"
:
"Land vehicle at the specified location."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Abort Alt:"
,
"units"
:
"meters"
,
"default"
:
25
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"radians"
,
"default"
:
0
,
"decimalPlaces"
:
2
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
0
,
"decimalPlaces"
:
1
}
},
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground and travel towards the specified position."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Pitch:"
,
"units"
:
"degrees"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"radians"
,
"default"
:
0
,
"decimalPlaces"
:
1
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
25
,
"decimalPlaces"
:
0
}
},
{
"id"
:
206
,
"rawName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST"
,
"friendlyName"
:
"Camera trigger distance"
,
"description"
:
"Set camera trigger distance."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Distance:"
,
"default"
:
25
,
"units"
:
"meters"
,
"decimalPlaces"
:
1
}
}
]
}
src/MissionManager/MavCmdInfoCommon.json
View file @
ed8b6aa5
...
...
@@ -409,7 +409,7 @@
},
"param2"
:
{
"label"
:
"Repeat:"
,
"default"
:
0
,
"default"
:
1
0
,
"decimalPlaces"
:
0
}
},
...
...
src/MissionManager/MissionController.cc
View file @
ed8b6aa5
...
...
@@ -987,11 +987,18 @@ bool MissionController::_findLastAltitude(double* lastAltitude)
// Don't use home position
for
(
int
i
=
1
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
i
tem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
VisualMissionItem
*
visualI
tem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
if
(
item
->
specifiesCoordinate
()
&&
!
i
tem
->
isStandaloneCoordinate
())
{
foundAltitude
=
i
tem
->
exitCoordinate
().
altitude
();
if
(
visualItem
->
specifiesCoordinate
()
&&
!
visualI
tem
->
isStandaloneCoordinate
())
{
foundAltitude
=
visualI
tem
->
exitCoordinate
().
altitude
();
found
=
true
;
if
(
visualItem
->
isSimpleItem
())
{
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
);
if
((
MAV_CMD
)
simpleItem
->
command
()
==
MAV_CMD_NAV_TAKEOFF
)
{
found
=
false
;
}
}
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment