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
7233dc20
Commit
7233dc20
authored
Feb 15, 2017
by
Don Gagne
Committed by
GitHub
Feb 15, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4557 from DonLakeFlyer/APMParamSet
ArduPilot: Load params from new Airframe page
parents
2098a28b
3480f76e
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
126 additions
and
2 deletions
+126
-2
APMAirframeComponent.qml
src/AutoPilotPlugins/APM/APMAirframeComponent.qml
+114
-0
APMAutoPilotPlugin.cc
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc
+0
-1
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+12
-1
No files found.
src/AutoPilotPlugins/APM/APMAirframeComponent.qml
View file @
7233dc20
...
...
@@ -29,6 +29,73 @@ SetupPage {
property
Fact
_oldFrameParam
:
controller
.
getParameterFact
(
-
1
,
"
FRAME
"
,
false
)
property
Fact
_newFrameParam
:
controller
.
getParameterFact
(
-
1
,
"
FRAME_CLASS
"
,
false
)
property
Fact
_frameTypeParam
:
controller
.
getParameterFact
(
-
1
,
"
FRAME_TYPE
"
,
false
)
property
var
_flatParamList
:
ListModel
{
ListElement
{
name
:
"
3DR Aero M
"
file
:
"
3DR_AERO_M.param
"
}
ListElement
{
name
:
"
3DR Aero RTF
"
file
:
"
3DR_Aero_RTF.param
"
}
ListElement
{
name
:
"
3DR Rover
"
file
:
"
3DR_Rover.param
"
}
ListElement
{
name
:
"
3DR Tarot
"
file
:
"
3DR_Tarot.bgsc
"
}
ListElement
{
name
:
"
Parrot Bebop
"
file
:
"
Parrot_Bebop.param
"
}
ListElement
{
name
:
"
Storm32
"
file
:
"
SToRM32-MAVLink.param
"
}
ListElement
{
name
:
"
3DR X8-M RTF
"
file
:
"
3DR_X8-M_RTF.param
"
}
ListElement
{
name
:
"
3DR Y6A
"
file
:
"
3DR_Y6A_RTF.param
"
}
ListElement
{
name
:
"
3DR X8+ RTF
"
file
:
"
3DR_X8+_RTF.param
"
}
ListElement
{
name
:
"
3DR QUAD X4 RTF
"
file
:
"
3DR_QUAD_X4_RTF.param
"
}
ListElement
{
name
:
"
3DR X8
"
file
:
"
3DR_X8_RTF.param
"
}
ListElement
{
name
:
"
Iris with GoPro
"
file
:
"
Iris with Front Mount Go Pro.param
"
}
ListElement
{
name
:
"
Iris with Tarot
"
file
:
"
Iris with Tarot Gimbal.param
"
}
ListElement
{
name
:
"
3DR Iris+
"
file
:
"
3DR_Iris+.param
"
}
ListElement
{
name
:
"
Iris
"
file
:
"
Iris.param
"
}
ListElement
{
name
:
"
3DR Y6B
"
file
:
"
3DR_Y6B_RTF.param
"
}
}
APMAirframeComponentController
{
id
:
controller
...
...
@@ -91,6 +158,48 @@ SetupPage {
}
}
Component
{
id
:
selectParamFileDialogComponent
QGCViewDialog
{
QGCLabel
{
id
:
applyParamsText
anchors.top
:
parent
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.margins
:
_margins
wrapMode
:
Text
.
WordWrap
text
:
qsTr
(
"
Select your drone to load the default parameters for it.
"
)
}
Flow
{
anchors.margins
:
_margins
anchors.top
:
applyParamsText
.
bottom
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.bottom
:
parent
.
bottom
spacing
:
_margins
layoutDirection
:
Qt
.
Vertical
;
Repeater
{
id
:
airframePicker
model
:
_flatParamList
delegate
:
QGCButton
{
width
:
parent
.
width
/
2.1
height
:
(
ScreenTools
.
defaultFontPixelHeight
*
14
)
/
5
text
:
name
onClicked
:
{
controller
.
loadParameters
(
file
)
hideDialog
()
}
}
}
}
}
}
Component
{
id
:
oldFramePageComponent
...
...
@@ -163,6 +272,11 @@ SetupPage {
indexModel
:
false
width
:
ScreenTools
.
defaultFontPixelWidth
*
15
}
QGCButton
{
text
:
qsTr
(
"
Load common parameters
"
)
onClicked
:
showDialog
(
selectParamFileDialogComponent
,
qsTr
(
"
Load common parameters
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Close
)
}
}
}
}
// SetupPage
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc
View file @
7233dc20
...
...
@@ -16,7 +16,6 @@
#include "VehicleComponent.h"
#include "APMAirframeComponent.h"
#include "APMAirframeComponentAirframes.h"
#include "APMAirframeComponentController.h"
#include "APMAirframeLoader.h"
#include "APMFlightModesComponent.h"
#include "APMRadioComponent.h"
...
...
src/FactSystem/ParameterManager.cc
View file @
7233dc20
...
...
@@ -219,7 +219,13 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_waitingParamTimeoutTimer
.
start
();
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:"
<<
totalWaitingParamCount
;
}
else
{
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Not restarting _waitingParamTimeoutTimer (all requests satisfied)"
;
if
(
!
_mapParameterName2Variant
.
contains
(
_vehicle
->
defaultComponentId
()))
{
// Still waiting for parameters from default component
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"Restarting _waitingParamTimeoutTimer (still waiting for default component params)"
;
_waitingParamTimeoutTimer
.
start
();
}
else
{
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Not restarting _waitingParamTimeoutTimer (all requests satisfied)"
;
}
}
// Update progress bar for waiting reads
...
...
@@ -949,6 +955,11 @@ void ParameterManager::_checkInitialLoadComplete(void)
}
}
if
(
!
_mapParameterName2Variant
.
contains
(
_vehicle
->
defaultComponentId
()))
{
// No default component params yet, not done yet
return
;
}
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete
=
true
;
...
...
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